From d33d5a7872cace2690e6f87120e0ac28d958c213 Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Fri, 18 Sep 2020 14:48:09 +0900 Subject: [PATCH 001/851] 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 002/851] 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 003/851] 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 004/851] 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 005/851] 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 006/851] 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 007/851] 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 008/851] 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 009/851] 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 010/851] 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 011/851] 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 012/851] 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 013/851] 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 014/851] 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 015/851] 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 016/851] 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 017/851] 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 018/851] 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 019/851] 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 020/851] 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 021/851] 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 022/851] 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 023/851] 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 024/851] 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 025/851] 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 026/851] 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 027/851] 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 028/851] 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 029/851] 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 030/851] 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 031/851] 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 032/851] 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 033/851] 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 034/851] 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 035/851] 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 036/851] 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 037/851] 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 038/851] 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 039/851] 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 040/851] 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 041/851] 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 042/851] 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 043/851] 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 044/851] 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 045/851] 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 046/851] 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 047/851] 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 048/851] 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 049/851] 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 050/851] 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 051/851] 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 052/851] 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 053/851] 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 054/851] 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 055/851] 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 056/851] [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 057/851] [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 058/851] 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 059/851] 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 060/851] 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 061/851] 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 062/851] 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 063/851] 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 064/851] [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 065/851] 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 066/851] 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 067/851] 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 068/851] 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 069/851] 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 070/851] 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 071/851] 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 072/851] 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 073/851] 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 074/851] [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 075/851] 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 076/851] 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 077/851] 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 078/851] 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 079/851] 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 080/851] [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 081/851] 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 082/851] 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 083/851] 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 084/851] 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 085/851] 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 086/851] 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 087/851] 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

    eUU}O)-pzf8eH2Z~2yg`D09Ztn!MM>1#tZuj0VIGFO9ToQ7u0a=Ag<{j zJSa;`3-V`w{Ga9HANyN5^4zm8+kL&n;oz@fAN`LX{_oP=(Zs|N&MKGsg(M%q;upy* z=D}iQ6jiySFm3*68&lM=xr-U}0t^0Hdg_h~OR7Q0tA z$QnX^%8k+tW<0xw*I|L8rf-uR=_*DwVXP`vpHwJHq14EGDwG;1gHdg?W{tEhLF(QX z8+ZqKYvP!yjmy#48w_DdDr+lJptKZji8X4L(b%X?ip7F7G&D(bOEW=HeXVE>6lWN{vbs~uSJ)RvweoLi{4U0<)}qL{RR^~sB^ZKBbwxK zcUg5eX0TJ)V59DT_o1I=L*ngxbar*gPyW=;(rq&HL9ke6oj0BXz&7ml!OkFyd-(8S zIsDmA%h4mRoZusW-vEpM@wa|ob`I@Pptv}r($ml$2EUP4xNM<#d6~fCRzNX5iL0>| zo1b}gdD>RM5xo%~{`5og*kgy~#PMU>UTfQ#bNScq+O=C=fB%E>#y7rMy1LNk6^}&| zyPn7d3)9lpEzNB`GCwm;a}u8K4kqn<)jdPcS&O8}E}|TS=Vk#W8ujwnqo0<)`Kv#Z zCm(<8%X+WadtQIv1M;@Fzmw}8b!4b7#@_Me{J80+TjZ6jo$W6VT z9OH_X87oV3vbMS!+#=2f@cdOMxihlX~C@ZVWQXBIPRrgdrvWNvmw78cR&NSQ=8w?SL0l~p8# z3rwoFb`8qR#Hfsqp40M@l_m1XOdK;=oU%h#PO0Iny;56~SMr>HDc81bu(;g}W_nT8 z>KYJMxAlmyp8oj<{-u2N+uk02kN0X) zAP0-inzHr9Iu4Xo7SV%Q#6biD8`LZUG^UbNd|zGJ)CtwuNj>cJPr9@gAlbp6_ESvy zEkYTfwwQFx@89~!A4z9t zI~hedXS%bTv&%Zq`2WG+$xucTt!*AsRg`4E|HaBsuLKm+qv?ugmS0kktLeSP`}Dip zjDC?gdG^_->5}@yXIi7;Pz-Rth=KHveh8|~rR5nML6_DE|-pDZuW z%hcF;SzB2S=ed`I=sjvo5FU=#h$Uc>XK`%}LGhE_V3s90>We$uPT z4#J_i6kBE}(-r*{N{!9Z+|o&31*oDBU}H=n=Wc25m9-VranH;0(wr>JP07fmbMo+~ zJ}F0!J}1vS{nVGe_P?#IO(0)<^wGnzyo^NuwS8bN{p7#-ce3w>eMVO3I&h%o;Ok2X z7O{3i9ly;{jI}y%8(5?&MFFE5yy$#Z`85+B_zcCFDbJ`f;dx-+vwh5eCyjG`bQb34 z2^NnWc}|{w>PenyFV_cR*ZnshkQ)yilACY7MWAkC>51*VDQFKK2`CdmY+(uNwY3eJ z*UT>fEH1L|@d7}jozXaxQPWsk*B~9edu8O}NtvD)Va%fal(nBF&22It*TG^s9M=pM zw*-k-VH8m>zpjwMmqTChPH-I_FIRF#^TJ6Te zUvai1-ITWan=UiJ!C42ODCj+7^@gY=Dxn5a=!%NKa&2`%+Bk|GRlWKCTbX_BLW(HpJSQ=U_ybuq?tWo2H2e!F^XF2D2P-`JMR=F7DKUH?1V z8-e!r4*Bly{h%B;a4?fm51^4rea&=IRtbOz#?Tt!LK4FMgS4)OE19>Az`7TU|UE36a6p+tt!zQ;m)b7cd7cF^fVM3RS}t&K*MvVxgxV!#Hr0H)&evy(p-X;I)2Yx6dtn}xoS!`lJiG4!BB1~bH2^P`N9?5`NFj5cwog6>@qCEHP(}JFM z+x`1nJ=bz`Gfg@6-Eaf5&%gF7zqqYEs8}k=Z-3;!OM6=jfnuzu^;%p_PG)O`vf1YB zKCXeAj*fTZjpx}H0~R5@%zya#=|C}ztJUQ=_S?BQ0takZkOGA_E6o>+SZnd6SB_(hBj@|(Y=$Bz3K6bva~q6 z38;JRnd$K|7gy~b^&GFr?943dzK@?cAx}R3=$C{UL+QX>cikgUHr#XXeO%|MkrHaA zo_PH8lmvd^sVBZ9<|Bn-QEs{AHo58MTjYTU-XI;FonZ`+DEGEuE@6iwJND%z>>V~m zu&z~kRgj*6{j#_)B~#-Um654zFtOj$zmM|tsqqU`j$kjs>&He;aWA@f@uEEW;CCC$Uk}S*V%2T3WT-sR`Q@Os31EkWN%qVZ>DhSHf~bXWI^LS6eKEG zRFDYcGwYq5{G9J^3c6IDt%sm5vx=Z+F%pZXPMsvcpZPL5+v4nk9Qua+H%f0`pBy-F zh+pIEPp`+%XlE9~*^KxjfJJpUU0vOfx%oM^$l$q*gzo%;EVFb3%9nX*Z0?r!t|7T} z;W#C$ke_0HBEil0W>anGRmA$Q!kWdat)(md{7VBClfx%D0{A6t*4bo!-K0KO0gI_* zBrt8&*u5M`#fArOFU{q-s*q!X&O3<5x2FT$q-r$#Hq^nWx#z8d>=>r%%h&)a15-BlfO= z9XsWQefy<wXpGIZ#3X7fS&AYn&lk z&*=TPbUj4o${IK4NI4HPz=D71XMa+T9eeSbhaU;QpZ(C!OK)#~=66&!9fLa_V@WnV z58kSYXZ?JQ5;c>mIRoK;F{yWo30`6L9$@k8nbS1K0C+_G@OFVC0^81xPT7C(78%^R zQ~G+l<(6CTke1e#IOmdcpI;g-uP-zbC<3TVPYko}jsaz+a77J65+onSQj<203*y)D z4Jy)D?vSbJc}i1{AA4TD@c3bwoSfL!+{JkhAOo;Av}?EAbN9W{)!h?IX4303*ZHZ* zNqG_h`^l5?;tNM*czD?QL|*gs5hVX^Ja9nJYUH-t?vOou_l1^WUfJXBn+iIxpA^}8 zguQ0T7^>_SW6C|eP?EvDx6AnD(=s`FE*N&TcJxbk{~kI?YRd`qX>5`H!9%h*HzgCJ z=eSp4PXO3@_L-+;_~LoCX&JtFfyN>)wcuKy@c`7b{WbnE~qQH`3itB zMNeQPmGO03&u$vDjhsIri;HtoDmBZ(!i+4VO&$9wt9mYeT&=SET4%vOjMshfV3C`O z7UblI77rL3x*oK-UX3|z@a9Eo1H1|C$E;|YF`>g~v4NQh0Grr|H|oOu=DJRqHv>Anfq5wu z1z-`f)`i(If;+N;=)XvIqCwi)yQQtYOUlhHvbH=c>#GZN|7>n@k^MVB-&F#`!WSbYLyFo(u2HkM3=io{M? zT3b7$wY`ID8|yWI#d-j=W-^M9*dsB8gBgnyiV6%44*y3!^JzJA`qUKy-E3_*#`3n? zZkJncyM5E)>0l9i5cXJAO)RVBKEa|YNeCiM7Kkx{ImDUMCmC=9uo- zA$Z;}A!=`LCj;El(ju*`ZGv_u2rf{6tu|kpoqy<|kITjL=R#IE^&i7Lc1KM1En8it zvDH_7)!WqZ*&MPX>+RY3g0bM(AuCc@*H%UzykK6jbbu|6{Cr8+$8eS?xI@j~GYs`U z001BWNklw_m?yPl_&YB=e^f4BI8Qn3$jBwix^dPbFvd9H zSwdFbRBn>C)>i2s*g?S5+1Vur4jz=9JBRddrpw#DcChH|E7TuIcBc$2=DhnuKrt{d zc!*;>J${~w0ynk6unwPlp6g2)u6o(I`&PCk8#(tvCKkh3&Cbrs$&)AK+}YDIKR3%{ z0|4aI^d#9J$OCnLt85?j^yTKVbar;r0lcN9RodFyxR--{SC-bLqe4?AIQpUlBC~*O zV$~H&Qf}$u{8*fylFs%v`I>jXhkqxvdvzs<&qpwRICsXzE+-y@`GppzFRp3N-W%lp z2OhLmN9bj#;M-k2nM6e54d;c`x?_I<08#}HKAZ7cvPU?`X9+{55I6a(AJv)Nj7VeR2u#&u{(h$?*u7I{WP z1+*$liwj&c-8&Ab8Q`TeWN>S13qdJ`p~ac$>p_S5I#^5tfG;gr#6jeYpV92eY)b!b z#tt};gw@Prt^gJZPhss`Q$y(k4sXw@r{*x(Kdf6cf(SYpaiJAxa)1x7F+{+Fd!dtQ zv60Q{y~PF=DmK^F_Ff*~Z0x--%gjCxbeh)y9DA*VUO@&JZYAHX!g%5k#o^f0+`)B) z01X>TsiBeYyEH#zwO+NX(`+iYXze1c!YfiM0I_Q-K}Ee{xh$=19a4)!R@QlNt8oT^ zqBacIK9D7Do+xU^J)ssMJ$SIe{r>NLga!K7KVE$!fM@;wZ~7K_$2q$^sPxUb6yrkjR+m9%t2}Bl zxfc5Jv4%~h(EQAQ18Cv3-VO%$Wb7WDIkmBQ1;Gpx70wE5aE_3n^a+?En`Bbrx!`^= z=Tnf#zvIBvKq1$q%`dY52ChM8kK~0$kuX)-MGo}u778*maY>2|WlCNz zUp&q^1Xc;aZG3Euz)is-*0#EmBN5BiM*aQ#+LJfoIb^U!EjxoxUR#}$mgX|0eF)06-B3UR`q1oIWdd^>S4^vhrdF;~B)JnL6ajcm zjg*@^q`hk=VG`u?oH+gv6hIGG2Y~{etK_OyIcim+eubo>gGKz?4RAbJ5!ZVT4%zz145!T- zToaRg(*_p7+9hBSdtYl?H_xb=nl))|Dht?Om@UGGK-b;o37#)+^D`>4iYCJiKrx=r zR5O{WoU49NZ;AF*4j$dT90ti<1N-Ij@F|&@^cESKaP+f~PPn?6m`wjVSWM@_mj*1_ zp#lxC2L++PE$oN6iNXgGH!)}M;)3-PBU%UN7cU;A8nCDl%gXY+9v(h1x6%~X)JnOf zLzWk3$p%8cih^wfc3>wcJ;G*{fJM~h;5F`^ioe&~+D&Iu1Wc4}BtTgYCM`0~OI*{< zSof!7Y*Mhuwiu0+b)YT@QV~dQX6=w{Xi`Tr92hv%DwS1fYHT6ffNajj>VmAVuTauf zZbFs^k~Z{jD@aFYuT<8T`JeZBQ?nbD0BS9nT4s~60o+`VnIsQ7(Z}sS{Nm5crAx!P zE&KXEU+E)&`i}4X?(dVamQNB z(dft<&$}>hEtvOOn!qL+>w5MygPUK{yG@T53wrEK%9vmTGYorO0x~$FIna^% z4w&ACwLj&yZfR-hBr`QTGZt9ombM=0-HCdn2D)U9Up}KHDK#}rE_C+plF702GCw<^ zf6GCQ$ujkMYh6}TOBW4oz-mDX>1VDRg@nhN;-ml$O>XM|nEmPO0orR&O48QeM>!^d zC}fnao&5w-moFUS^Gg}5{9N*%Rm*vAifb~5LoPP*e`e6HJ!28>cLPI*q_NyC6PM4* z*vQFXf)d^~afFTYDblY#t{mK&T4`u(C9|@+W@mh;+vQyy?kJ-jUS7=E7IMeO(I1by^ zjNVq~F6IZ$iJg0HrGxI+rBej6>ZeidBbopCvqT?$@=N)5$hN%DL=*fiESbgl5<`z( z+Z85N0Su9(1TaHO2>hER4fwaQi;CX$3;|eVBGptXp5#yK{qY)=qzYo{kujwOH#|lb8>l#L;snd1_V2pP+{DAx)BA-20I5M65ycJXQT@qFR|n zw#V@DkfdA$tRhNcz%bUW4N11Z@KQYz(sS3rVwL6aMT14h-dOZ_ zs5El1LDvP6epFeK8oAkCsz1*f;iy|^$cE^yp|7(#MI6+mr>#d$`1w{_Ky4j2I|Ykt zJnVv0mNK1~_H`2)*YEq?c<`Xv;wl?gHRdp#jNy$;7L<`2sbm)g=N(-;q?RCYit<{F zFM=P801STc8JTEof(R7JI?#d{PLl{0>nTH}l&!5pT3Xxbf(pso#@eD3>NVI*4MtMX zsKwJ3teY*r17Ktl@%3N-<)6zR{6GJB+jT2jZR*#*|K%S6fRJzd_V1QE@47qFHo!N` zYVu4tCb8DT!_cZr5wrK%aEGdh~8a=Dk3m}rN zs4%)gEse4|I22P>1bYht6R_TpMj|+eF$3JqC`(H}5~hORWPQ%z;HejMcr=4tZnqF&2=9`)9VzD8aQ@rKoM~odk)+ zlA7YMrn9z&t#Pn^HFkmh_gZkmLvl%7pfxbVL!isFtz)m7$t1M$fvOLffh?#jzzhJS zW8A>jWxyg$#|$hkEo?1;v*!~6l*|#JnQ?to*0P1nWCARcn!5aI;k;;WCr~C(gzM?5 z0%Nk920-HPCAEMCT+?-6hm)O64my&7vi&h8G;r<8_+kJk4J#DQeH(i+6JSzTvg%s_haktv7Rq!`U;x#&ixU^I;|#N!f*-u~vq$ z3D4*^6vTBB!~twT8VcZm`v&{fyW>UzjLGo}G60=GV!t+goQ<$m1*#@B0E-i&0E^=p zu;`4C9-}o>)wH(vbN=G>YT#58Yl00x$7iY-M4~DmieAK>F(br-TiwBurHlGqWup& zDQ)+h%1r%DBS1`LenkD=&_u#zhD*ncO80(-v{I4U{TvN=%HAr=jHN}xroEx14*RX z;KI!oOeS6R+ayTjxrpZh#g3Z7sX3e}#7w>7^^4k{+f3#{(v?>i)`;(QnP-qDEqvb& zv9(6OO-*fFqi`mkn?Y@_O2ey#;G5=EnjlJmqADjenZfwpN<0u-xT=Zg?}~#(b0_x% z?((XvS1MEhw6yQwJil=61zA~K&|a1Xz}e3-?XMWJfY+JD%w9LN@6KyV(NqIOLDOBS zgn-Qt3YUCTrS;P*@CK;yD9+3;+6k{}A4MK&=F;hhxqh#ni%I35ab{P~7TLjp9x0aD z4S;a-vbO`w-nAM4^u?2`u1!p$9oqbq91#wUJ>O1gm1V8*S_BoSOGFT?Mf?EG+D?S$ zpJlqWR#CIwu)l^3fh`HF77SYQ=H^z}F?1s}fRnh2W)3p1fhE6cJtuRzg3qJk%NMg>EMO_?$+3oLPvd8-TnMgXExLzJQtEEUl= z6m_}vF?(v+Q6_0v>(|IyJpcohfulDV+FhyW%+!RO*EK`ESy%Dl5tLsXDbk%^?GRM`TR#k972CL(ae`9Y# z5(_~HnZ=TW#raSJV&O7%(DAYDhgv=>SXLC(1oD$5irjD{w88c4c2nMna5^K~& znnSQglc7cq*USGH(7;?rlNlPoqiv1$E_Kr>m#IatnDh&?fX!J#vf2g=wZ_RLo#vs z9A6WZMh@8d8Lw-nloj_6Bb9}@No|+nfu(`z_=wVEZ?5;8yDHllXc7y+wOu;8caXi9 z8b41^T3=U`&c5AJS6eTm!^eYcd%GcI8k2-6lZyr7wa2I>AHNWoH+RUu?whF&7(RDY zW+sN63{N7Tm{dtYqwakwt%x!|m7rqofE8A-Xe%niF2+aKRBn^OeRuGAj$C|^^Bwa> z7b4=YiW+bgOWHFVo$#mO1z_rXY9h zoD82mYIVm}BIF~OfFn<`_};TAwyU;Z+Jo~k4q{K1X-PN}Rb^45Djbw^K)wzj#PuzD zrqG3ZnP(~Y07GEtk&SjqYD%c39aQ6(?*wBw0(*Ups&gXCm`S__^2I6ntUGc#jL!b& zzlU`Wb`dqiFpc3H%gxB}J1!)#11Kcsa_c!&PPmT%K5O4&^#^dUxU>Z6shiuV+6T#N z2%AtB+c$VK6$zIwouTT1aS2r!s>}$4mF>kjf$qx~nZ0uV)HayK>`l=A-VR6{UYIC2 zgwW`o@{lT-UpBGKM<~7_1x1eq05*Za8mL)=ZgN=gI52}_S8hWH(xEL_#qe^IS}}<8 zJ~a-+yja?5di-zmcdJQTHy8I*m6mP>+_={|G9fO}KK*wP|`tvSkNLiIGZbWTQW; zvX%p5W$8WxTt;98d6(W!xKSSp{W(FK2XE+ai?&7Dx`;ufNo&p;2V3n7rs_us}(sDa%2=OsJagik% z_`^sjfcfg`-Ocqma_)JVn;j28z=sqyiyd7%Wo+aOS*`S()wR08@`{e0T|6JbD9+7J zD0^jPB7Tpa{L$s^HAjB!F2w~{S1?QmP*Xk?8ycmncMpN{wKh>mh=9ezb&L(4 z(0OiN2Dkqf{S-DC71y?r)sV_0Sq1sc*%) z1z21{efjEA0E?krL)bqRKmern4;_-`mM*z?_F1y9UKi)`NL_EPoG8*y0@uE>vJewD zN$oVQpS=ZPY?Iu}OFKn#yO{xBTw7a5zwF$52cPHplTXUb)M(s&wkQR1(BMpWK<0jN zCY`Q!twCaL58W?CpM##MS_6reOOQ;0F@xL^?w)8SuQJrtgqa;_ArKhgEz_8$XS`17}1(` z1Bo7==%}WvbGs>_mo{5pO}}-`U@?DF%;Xwa#6m|V5gEq0nK5RMGW>Hjtwu6=vYVZ{ zeBtnjVCT>i(%Nm*LT0rFiK$9L!$&o+ zc#Tgy92y3+kbyRtq^F0AdI{>>$kR%eB#Yjg*>N2o6_Q7NoHe zwOsX5F1JyBO4qQ;nyf5MQ+^7dSS~kf3j??9H%Cf$MI{KO2}bPI!^6S*OWNjvqVNCv zcYc%2U9W$;@JSG;k~t%5q&TfSm>xnCNKk}(!k5+ivB&5YHbqiX*xd~A=U?u z%x1Ac9ir!_RSsz{qRfmJ;jD^dlgP3tz_R*EOJce!V;<=88M?EmgT-JF;mNg_pN>ah zdX^*V0Odz7#RQzcFKWWXYlf2Krn z<0uD<`nN66xBcFONv#nzRgQp-YLSla!PvfHZc>BTx_asA+e5GjkUM(ugtc1GeIO>J zBp9Zkc5HERCW1w>tYD{#lnp}mJT*Qn)03CfP{x8tXYMs9kIy!p?4nX_Y75fYGf1!q z_ICKpbFwfG38nUi)C5BecKs_|M_DG3OtsB(Bz@}YOYAr2Y6wrBsL4zk`qc1wpyqFK z^eov{_F5$H)?~7mt+>3GOn16VXSdjdryW1VGG)-gDw1`mMjI#1V$pVwLko(+8i z{h#~(aaePF&*SKwHpROl7K}#(6$Z~hPRX6 z$E4wetCBU24=0ynGcy@%Hed+=){2EjJZFM7W>0hVfxcOXzjKX&53jAZj&7zZqe5m} z9Zq=|uPjJC>Y!G@R;(v3c-gFFcw(W)Q$B~74bH;CvD1c@;;r3MDwVmY;2sDm2z1|S zQh|Wa9A@pHPP3-zq38!8YLpO2BA{lLy;z{sZ+&e^YHK#6r+=3$&*MN`mtvuw#u-J} z@fYgpl!{=Tfx1f@tZt0s1K@p1omJG8i=dCS0;_AXM0ZihVKmd}h2^lPR#s7EANb6lTmK_u0zKexfJ7N;J(3d% zAc73qSVpg93}Df+r7&#*6G7%`V~y^^D{vpCBs&*|rT_FSZbp8nQXtG@9z--n0btaF z2q2eIT9dheS@b@Op275trXO4gVhO6<7Cosk3xS4Rm)4C$qZ=9%Sl>j*OW9Jy-BHOR zYV9If#YSZnT?L@+H;U$rT#*_|)irq5_|4d_B!e6ee0|p0jOymap~*abPXvDeg=#!w zGE~-&shN%@_~6h8>8qN4A?U^nwD)7ecG6*Fi@`BJ5Aaefl^Kwtz8eWl zH-yo{$N+1QbLPOJ2P*CWY>`edmoX`ItaY!&08HMo7lcBX8P8@uRn2S7j>ZkX*l0U&cDd< z2xT`xE}8?2#?EHJpR!rr6uzOUje9#Jdg1%I8dwL%NCfS<@gDBMXOBHDON($swLa4v zTdW03IB+hZwGW)sk%UvHNeYy#MlO>o*(!GP8qBH`e;mDPKv^f9f-^khq5XI9de5Ew z0-bI>c~uQ`W4=QF{g=5vz=%_bmqF zsHQFi`H)Q7n7Bb2&kmEJdJ8lMi~LODMcudkzfiMmvUEI?pj30$;2c=YgGY^{VHVlN z(u9S%DgFnyXn$P3-|N3MKF%mRk_4R_>bbn$OG9X+XA)gMZ#B+<$qke~W^!Yn2`G_N zs)5R8MKH%pjcs!A-1BVZMbCwB4kSx&h1S-eKaiV0iRsH}lf$%=qU?5+rp)>|;LLs=wc6)(yWjDK^(lu zhG6nQ#>NSZjSoT1#yYQq?x!d$~ zkH8BVaAY*WlCZw!N>Z09EN#dNS+RJzxs7hGxQ6xBCDuZ1tS$5Nz^HiS9smF!07*na zRN#%WvN$apYYS2WSZqVztCG~$Lau5J(#?E?`ggkgsr4}qS2ea+XCRt?7Fg_m^xytK z{^HO7^tHaOUXk~Y=lLxk_!sh)x4bpy(rZBw5&@R=#Po$T9t(HSBKjEQx5I#zyN+2AM2 z_=23so?`@y=qI_+4I_R}EO76mHAEy-7YMoTbP)M-bS64;!8H2U`A``9pq313bAOwyKAQ?Qup;(y* zU!ReI^8nJ^6nS=)1V9mqNVsz2yvLb^-vRg=*mVxKd zF3!)W>mdzJYS~K>z;k|XiqcTD;ZdhsP3)urrOVdhxEUyMpM%7G*uf3fSZhZwrLrjZ zm>fH+?N<0&y=0uvkX#~xJ8}6;c=rA*w_*yzxfs=<`Up1BEcs)?UZ6CU{t)q1u~GU5 z4@yVx5DkQe&m0Nhi*M^PYEvC$YB>!=MIQmtSda|CmW>JN|sYCmf=v3XOK>S?3+-D;4|hgAnUVz&5N z%nj6>?$~oHCB+y&fJORX*!Wh{nukXfV#w%hyy>YW`$LEVa|Tu1TWnmJghjFk;Ba-B zESLiyx{3$T=&h-=j*(!>+98GHD{G*m43%dGl{;V-Q-)DvIR}kAdvZzwPhxsfNYAR| zBbBV$w~-WT>FDDg0tqUfbw>4(Q}pN_X3xv!t+)U2{Wm6r020^9sv_~MF^JVGa_p>i z2G43|8lkj+<8*<)Ge18ooqc;`ZDmzPE}r1ts7u0G-sJwSgT?&R&iwnD!D0#wdCUt&#- zEH2FOpam1VzPfBRCP~d^a$xA&CV`LNh<(oiBb@-7S{Mw#Ccm<=%6b8?6R2BkXe!Iv z@~p_(62W0hd#98jf2)OCnFglbcagzs5mwlieP&Z|I4?#Cu*#9`5Re-7p!(%s`Z>99 z{`?gu-t`~8{3CGdZFk6be%JT0XI032d;JcWM7Bp+r|gP-2G>?tKS8$5H)pzoMzH8b zJOLJ=n4}38GD@(I#z3;=9Ivj@Y z#j({u$|PzI61-gojRaJVqOw^WN}AE-L4@qC0Y=m*ru7kSXhVQ`1y(VY-FdXg`d`bk zYtwiH?rKV<20$1KUxxtB=obhut;`}>M~;_{AL~-gLLKp#_gQ16*jOb^0>m1$uzggU zhTKyu5VP%C??dYXmBni!&_W>XwQAYGPJxErr`A2=JymX|d#>-H@lje~rF|pJ9S6J? z!I3cplL@mOswZG(vm}dilMH(8%60DL0(J&$mbCPs!CRbouo6B)rsSZLV;6(@kcs!& z(+pTta21kxn*B>yUO4#{f&;1trg~k*;$oNeU@9?8QWGWvOk~CFb*zKL*`MC6oj>_BrG7e6%8g~#R01A-KBX)Q zYqKpGf;Kocbp@H3ylg;R>s{R;Iyk^rDl{_Mchduu{GT}b2-#wFsE$mnj&FhEh`qbS z+F|YYstjqYfAxf!-H2^B5lmj~boBkmc9N)h469%Fe9p7hF4=qVeyY{Z9)FyzS|UU2 z;cE6_>6-Lny;Npu&vw%z_utp268D}c0oJ-&>I5vhLLyIOV2!|h z3iAeREx;H*(s(#wz8x(3x$L0LKZkYgY9C`&9V`ZB5d;#!BE~E-v0egGQw!s}by-}T zr_up3_KC~q!`$Z{l#^LkOB!5l9=?`-{*u9>7BJUy6G7&Sy_HxX4U2OtnyrG=a}RyB^H8O6R$H<4HE~vC*1V# zYsE%vd}T78njMdU&eg%9+o#u1a*C`gm{%N*bbw1g5->;>)vnpU)^Ug*{Ju?iH|aqT zz?u}cGO2JQ!GdmU@0N0NE3<)+x~;FyOMNXG?P|>;0#dc>*C5s9sA=CtH5k#_NDcIo zYw_*ArbhnuZ~js~`Uk(Kj&;{RUJ)YzbCmD+uJ4uGZo5;jhmR14haT>jYwTkLgDN-G z0C-|c8qIckJtA2)GqnjWp>zg?3{^pv8*oG!Di|+iF*NfT+h>Gk^u{m(2$fsfq^+Yz z5QM^L4{L7~fk!2_h6qWD++55rsWbq`dZ9T6R04@fh}T$Bf@-ZlcxWSIX|A6Lf6O-MWgU45*4N6B&|X&{^4M*xfERt1Y_;!UtPlk8PCxr{-; zo}m)OInSKy57D|fkh^@%=(_SM+l@hsg6`4tggUn@n>lD z-#V7L%&0%myo#?1hImB;cQ4aLToEj4-bxSZ)SLwi5CE};?A3~_p-y6bjoDO66j7kh zpRMNlmv~3)2=C(29y8Hk7wMeJznxFdWf``uip)3FOJ3k(m z%t3bIOhsf#a7`G$>FFu?&ENQSdFJUayiC*h`k%Sl2)y%MUnBp=`@dO}2&hlsp;559 zJ(YJ*j%jS5Ieeov4SKAiuGf|$g+j>Uvu1INvC8dUv8FE=bUEcBcSrSKkrNHH9&!3WXVPY zC6)ki2&~Ws0uA6fE-sI|FQByu43Ut8LAxawu2~JE0W92Sd)I*U4D4e9b$sNMtS-+7hwi=|H?oxi z=GukRPs`Zw$;7QZ1x$&VkkpW+Z0{PB3um6C3>7AMUH$u*h!{Tif=o}sxiErbCb23| z0hnsR>NeA$Gfi{^b~hOMV6SN+quANAQ${bo$eK$q`r5Qy>+SUUf#GbIp&RZbs|Z=G z%kwlD9_Q~?v1T^uf@vRRor)c8Y^uop@MG-NJNMis{X++2W^z={9Q&NLCUNF6JGQBj z4R<&O#IeOn3KqdAHkCVNVhrxDsJFKI&ka>sIN(AY1Tb*R-S1+Xju)T(l+?h~#>#}0 zP1GbHt{0y>x&}Bu;9~F1;JvOltO=K+=8Tg;2o5+^BdG9>}#3Dy(X>;1R9 zkuLEkj~=Eek2|@iahE4B(mz`bELMp|b5|N!<@DTfW1Cu-C^E^0@+TPEz}AQRwGZYG_cqe)f1%i5vUBp$WKW zof$~zCZzSb=9#DE*MH^T%ltev?AJfOk|WUF-6KEnuYXi_?i}JFPmpMA zI&GxaHCVu=uD#uKW7b*$wW;>ri7q$wK7*NlgE-v60jJr)3|O>80}eJgwkeAio6!Rh zflch}8IY!Oi>y;RH$w@XwukVZpK9~(z$>z5*->^WSIXFU174S(GWaym7n=Ph8A~#% z$n;t*iOYhr^3$xlnrBYKer8`p#e-VV!%Y%(TMKg&+(+RejWr5o18O+oV$95ZO+{MU zI;C%5uQWE5WoF`ntgXy*eG)9PKdOR8J?u5fmys5knaoyW6|OaGrfH*k#JO7QS64va zM>s1tGjLy8n3j2S!o*&Q{WHpJlOA`tqQsq5>z5*AtqK-1Or!n-KoN`x7&9FHFeO24 z9*_|OM3b1tncxZyy&n%+w0KVET zv-x=gU9wRJ3}%f91sGDSuQD+qH5*dTWUnT65Ky+Z_ek%~{RBHOdO>o)T~p!ExqJWJ z(ok-d%jaK|;d4iV!Cia?N#GcOH(D7Cu>SGf$!B=~U;vt0dt~DBS-CuXf_sTOF(Y}! z{*vn(vdXW$-=w=5daEBkVNHnTdP*W@>D#ei28IsE+{~z4zVJNVgT3Em8aT6VvaL&Y z?SCDOdf=dm51+R|mbWD_VNygJ1nxy?@40-?lB#r!g@#0T@4?q|uQ+r3aT&jKDrqf| zxB&;*qkfOlTz5bhkDfJiFEt8E6(L$;QYU*4-6sP>H_6e* z|5hf(&QikciUnt+>E>K0N=th;=Nje+CEKfNO+e(TU@?LZkB?k)?yO^N zU6EiL>@Zv~pMUD(R6*z_;WR{~EA-o&6MF=bUh7=tx?&t^znkncG*R=W?=`3`ED|^RBIuYoTI$nlVPfyu)Wy!Ujk(A zXC8+jCeb9WCUx~|bw>r@jtMjcnJVe+8$85oy>$LXCa_5OkQh?;-79`v2aB2EAy~}U z`o$ne7ZO`cSYu>7U>d$y&p%`&nW;(Srwz^R(%vy3qnA!nB7~28FyKoRts^kuv2gq~ z3Y4y%!@1IfzE-e^>xQIBrKp;@#0JK89kq~f!bud8oi%Ce+#yTzGh_z+{i_3N-f_4e zZ1#L_b6QiiX?13DyI?U4lLc0E9;CBuouGdd4tU%Tj6!heBkPACb87sotgp<6mKikB zD3xf8b^wp;>3oMg>cCXOB<|Qz+7%@4x)+hvnmc|F>UBob;Oi+n8rx z{|)b#_k8X9SPO@GCe#-zi>MB39ymJ_$PF5R(OO`*{M4OKBde%=jY4yJG#0kj6JA^7 z2f4E=o(Xkn44ph#pV&w?k#)5V=&d?K)&uNE>eA>n78-QKRlXH7zXZcKLW5QQn|R7SCj=3oF9 zXr-{cgeLGFq{RRw1}%w-CAi?ZDM)1QnAq@IKsLVDM2Eg}1e`vW{#h;Qv$b1Z^TR|P zlWM3%Ez&U@U=e#Lt_o`q%$AzMX??E)Sp4DGl-e2aI8RgOUYDcl_gt=K*UzC=03YOn z*rTzx7tx9a?O2*A_eOs~07twQ5>+%>ZLlH{M0oYxvAF1ht{90283*>{+jUCn3AtbK~8V$>KTr zbaeJ5AJ-#%5)6RO9Q(W`6fEJMWi2Bx)j6bK z(f2&91G7Dfim6&@Z0?lh#RZv}9?P)NdGjEE`J3;4mrRXbkQbi%d(KG?ttE^#L89h& zh%XRxEW#bvdPh5ZmCCa{iRI%LnRg$MY>7)g9#zoopu|!+p;xM|8_Ho@yXDXwZ)IIG z#_!yTFS!2K>>o_&7Gkj!fXDhu2aDDA^l&9%3$pKo);qC1LrpE}iR&mq)p|wkt*E9{ zUM~;nsg`oMUjTayde35G>2!LVeB6zyymm1Gjm|haX!Hb7a7J~PRIgj43^fAAR231= z58b01$}Q5-vzuxI7(lUGK{^g;n<7hSxD#nOk4??t5@_zhWVii%)ic>0VbgMvpspaW zjC~mO_d!zC(bx$6H0d5}*W;wtrh@kTdb|!6vtV&>-yH#!r2q&AGe99sUGO!Vzfy^$ z{a$p#@HPr2Q#BCO+SxBn(AZym(cIW#Peyff63SS)_-sRmWP$HzC&|_ztXllPNmP{= ziEjEO%XKnPM)1K55GFe{`zi@?S*LGKU{v9_=Ps%K9@UIz;#g{6;sy`7qQiJyrkhWh zx)|_en*nbXh_clNSF{F(+B~};jSVf*+KKwF7S?Ml&riwp_&I^U5Bn=x>jDLfDn(@g zZ_bq7ESy29)kE^I0E>utk4CaJWF071rB!}K&Yn3dANrXemGLnx$iM#a@{hp&8xP9A z`hg#juC8tdyTHoOj~N_y$ps8eFm47Wf4v37njr#brJQ8+FBy5 zuW(1RbgpL2GBg_s@X^}RDQ#W7(%C)0fNg1hQWnwPMPN9kCLGQxdcP<=#I$PYN)pBZ z7L!^9txvXIPF9!cSxg%HB(A9L?5ZX|v9*Q=U|J7k>_*PmAbr{di0GZio`|gk4NXmL zWD!?a7sx7NpKS%xI6q0o4&&9_+$L?Ey)wAxRt98q)59`x=>$QeGK!H+tRpDVu~NCN zO6r0XHJ`Lgg8J~B0)BKhD9zx*;HD_B@rTL+L%O&y#m3wu;5^A^i7RCduy?6>kFp1@ zf=Hg58(*XYX0P>HbtLVYn$@CR8O3q37xcQZYfiJpA!teDPi|zRM@(cDodFL4wK3v+ zjnR?md8Ev#gRclOQYjJ&0vsVAvgrXmpHMy9M&05 zWfzR~$7h?TTEl1wo>gt$?KPJn{I*gHO}uCiHuw+W-!LKp(}=*n2~OImapdbO($%+% z-y1o1RHnu+5=`Rv!H5GW_U*WV$$}F{9$}p#8JH9-Za$jzxD=teOkBKQ!+a>V)b@}IKkPIjaOV2dSf%`mohZNp|kN zP4*tRmt%7Lxrb>el-BsAASJRkR<~(vRyxPi{TO`}%Prk9K6;)>T~7{%WC{01b%DR_ z-gi^V`OIT~u63K1{7|I_63D9XXl?J7rj~Zrf1>uuAb@b@uG%|4Qa(mF?vE&*&N~>`a3*i~kspky$je zwq!oLawWWBqAU(cLvujI9t@@v&taLZs8-BGPC=p9AXCADL?zZU&l>|xRQzQ70*2BK z1BaEtU~b6u%1SyrNf7VPD9wf?$#62mw7Ov*#Zsl-8QqqDr*(x^)^4h|RCIR=WH4 z5>QTzKsKQ(NDG^_4iS@zH7`8mv{eKopkA-HReO!?jNa9l#kgglWk*@+>WZ?us#fC~ zNLT2dRe{|cWL=aH6uD`z;U{}8g#pno(xUg|VykUTRS%im4Q5nWNuZaV=-F3cV}^4p zfFh)*_`u;;ZfWNRip^wl^o*=5&RTD~f&xRhEkcIch+c~d6!GsMbu&wU91bjGPc{|Y zHUp4CN$r{&&;mu>{{HB{{ulYfkN$4;#krjadi}NA9sx)czw^64DEB}3CazzVoT6c_ zyF?}?8U~v+JZ0r#z^XF7$Rs%{?KO*FC%Sug zOG{gaY^*QK;@pHRFHV!y2v*-Flc8&yWwN!7*xWtC+S@!tF<{esW`OB3LpQjwz%-hM z#M%ee^H`z1*N?bkn;JNoF@$CGJ#f%FuF>9XXl7quV9P#Nr9LsO9J;@>k97bzcKm>p*;oITh~r$KvEL^JnL&RGc`hR1qF+~pa17w0c=p6oGCgrA**~ma)1_zz z3WHSAB)8tI-0Mrj-?t;GzGHikos~J^x(b}J+Uk37tJ#qc~rUu=7B2KF`XbY!2@ z!$U=9Dx3@pk%oZ2@#_|-ajutP&@r}NYU_(^MFllPV8|>HLQt3{DuWDD!D2oEL;@n1 zZ27sUCQd%56*wwbbmOy7l}2hM$s235A#nM-eawmRGBi7?;e0%%O?nPYOv0p~h{X_SRB zu;g*&0)?z({A$=?+kx0WkY9*k(O5peFEm$GIRhyDL@t!Sag!}^+k-^47LDe+WOZ$s z5+%ysC|w1M(8%o(v^6H9X5<}&#!Rys$y^({-->~}+V4A9WCpmdNNE)u^<2{ob`g>% zn8MJiAAN%wTiMoQX>LZFnfZq;jI@p+GfYXX=BDp&F_HW_R03s;p>3edNIEd3WJnKa z94;_3sH?%oqy^_5h*3ILYG4Cz)IO}O%q8~x1?}bLCO2RgiwYLK?;Sq7*^LJAnzbqx zOEgD-VFzkL02sM3q6W0GAtS>V^lX)(CNBXfl1W^W#b9cKb`lB}Q|Gpr@sGg~*Q1+9)YUR@Ztv)m zj-DNqz`FA;5#u^G1H2~K`%1v(knqvzM z%l3wvi6{l)Yhh(h1C*q}uji|MKOpmto^id*z#@SIpaA(B{$qj#Jy%OGpu&E;&N^=d zmAyOm(Rp%ZVTK7iY&SEL7YP!vt^vU63o0|M5%fKc{qvB>(!)LmXId7nPK4=42yt`Y z*MlD$jwTe8`9hz*TGre(wRADagE(X8d(0&oF7Z=Gh^539=}Y=&@yz2V%}NdvKG~eOUml0h+Ul zxgLZe(2Bqj&lJ+U?tavowuEvG)LBlBo|7dQfLNB>jUk+o@*rQ?O=Yg}Jx|2s1E>^C zI&+?8_ybr>Ym$<78No%jwniEo%d+?2z0%XaS7xV2cm|@T5mL~#<$1D=H{SXtvdkx+ ze?-n5f0A|2*z>cTO>C<~r|~)%sg>!Vi|dC(Y{wqdla0&yQ|R4ymJ&T@P`u7g8HZ?? z6(ws{pJ@zm0E?m3N`=NIJ9pnqqngVXUX)Acp3@SO8fzcoCO*0H3a~FQpu#wuIPw{p zn;NxRRF`w7F;PApoM#o2_C1NhA^aATJ9RuqVHN_Qh&CiJ3j$DMEm#JS=0KALZ2?P4_~4t@ZT|DH5>A7*Yu}*XikePg!)AZu)cfy)@JqdNS4O7=zT5V9`M#o{KV&G#ztSTW8m;l}4z& z=CSP_0ZNGAeqct0`d`L)7miuy08h&0lhN42veJKdqgMI9CU6}Pr>Y(78(xR4%(u(X zH}_oiUX-d1T$lc#n>b%l|4cPtj^s+8WlB(84LiJgBET>0l`2@QGKd&3m788!=9Pjb zEvC0jwy}xGnu9$=e?EXkWZ2QT(+m2Q<*x9pn~>=V@r;PMm9@Fpg>#lVo5AaT4p3*N&{8{5SC5GyzcJXE$y9X=39`3*)ht(VA|r$jQ4|bX-#0VomouS zsjJFR8BC^bY}pz^HxEdiQQcU>nH^y& zu`?3RHdb9P>0XqK6<(|NrF$Fx2MHo%mH2vTaZaWuE|4u^g3+8#HIPw2=q(3=eAAfE z3|LI|H9Zf|x}b&f!BUeliU@Au9*QxH&Zi!PY!1*}^WtF9+bj5SM|tPECJmS{3Bcdn zP&d`wcpZ~|_JCR0me{yngF{W4f}MjQ4_k;-Dy;dN7&#-0sK<5Lt{b1QPSJa`>B$xY zC{5_3362yX@@F1&*}B%iUjsL1a-Ah`*H51>l%*p1S18JkJvYnF-M8?$!UP7YAGEYU z4Q=i`EM?u-qxz5{`Kdu47A%itIk{db#;^ zZ zRebjIe=Vn;e^k#8Z~tOo5y=7=907PE0pgCjZ2WGFVszTnI#8|ewS-@2CzGvhPGczD z+kI_k?>{C2mA!TiOS#-3cfR3$+;;)=k38{rYP4ucE8h>oyYb$Xyx{(2aa`QPkd#u^ z^@<-h=k@*VnsD|}b*0`Hbi!wA2W?a0EitqV!Wz(fPtl~mDuH6YFQ8qFwR>TFTVs!2Pllz>%FY0~Bky3_C#+*6Vca}M&kMhIl{3fr>8_{o`zd1@ zl0Zo!*TJGoq}71WB&!BAU40P}!5BBG$j}Y1V~NB#>J{^bHk+j55lLJdP4(J~I%@{^ z-HBPKcb>`WxVpP4{0Spfz41Ndr~ngXZDh{?2#0BbfC4~Kt-_4m zQ8~jpD3zKPq`A3O8XKFWP*;hqG}z7nZ4I=&0k!YeC(i>~Q<&LsA%Ly5#_1|OTUc0> z-}v=kmcyU@)N5~reTDA$Jzx7?`MR(B1_Jz4b{ZsxRtcZkkh@*R#3w)EPy;KM!2A zURZ0mQMZkN6JJkWKF^vSFl4xXfGgA^fk|9mn&mS(6|wVxKr?VFR0Io0bNjx&77u?HT)!K(siK$WHeiFnulUeFUON zOihlRWB*x##kBs=*g<7AW2Roe*6kuFB$DJC_77yP!GHiTFE1}pvWdSHO_}1{$^?y} zZpgJGIxkX|&A(Rm&ZJN@dUBSy8dy}|rO8tT3+lG%trmQKDzk!lj=qC1wc$NNvO6~= zVT+ud5V?nvv&Ai=CB ziwib!&%t|`yg7gJ2^zWq$D@He5gYHXz=B^Z{$eRonO_~J94V%-zZT9fbj^((WI0O1@1;Yk}xlJ!*NGs1nL zSvVL_IKUoz`jebP+HN5B!vwHV8FAcW=mc9^Cj+~0mfbhpDMz0C80GQGoEq@<_8IoP zj3&3amdNmu{XfPPaZYOZ4d0VG>FgeoJ0JWfOzs|i;_u|t^M^U#O+=LJa&hfC6P-%O zBeR@!{KZsjM9Z0Cql{fT!@5}}957eNFlvbqWU3Fm{aa*lVMY#r{G$ZeT8nCHn4knQ z-F~jq87M;5R)gGJdojmG@6p9Nt`SeR;QoU|U9(47#?QvD8ccKbgN}iPu(dU^`^J0a z_WRz$c<8ZD{GnVPKA8pF9(U@-U~HnrRF34(H6E&yFbw&nKlWS@S zS&2RHeL_zP4?0xiG#R2Xe5x#oWuCHCUPTiw0+Od zX!|+cp-p0~YhM)@7$Um;78+&8-dm}n^Svc3&T8jhmGd-F+Dbl| zd101$^a6dDoZzsBd;^(8%@$+bsXWp0Md6*c28U4=P;ET74Hnbvza7-*7m0;K0Gr4= z@%I1{aS*acRRe76FPTOA=I!h1VDZW`A_Er9CLW9-Ym|c9tObSjMP}Yn^988|GPhtR zw76UQkU@e|Utdx)j6#XoAb>setOL7PSzDGm^tq!mUP0Pmx=}961|+HtW_Ck)D&(kO z84EPkKutm!z_O{uWG6Trz(gkvw;_uys`LVZ!_gzp%D?^TACdVvWSFmid^ty;zkfh} z@P~g)dV6}kj4S{~51f4ik97gw)w(~xHpYX z>K-?ZX%(>8(A3N%0TLo$f^mD09i#ss99+F7UX!$`)I?*?*f=_ZR!?X!kTQnN9b0{V z5;&0^O6sL@8;u9)TyM_ukO{4qp8kDolK=aPY__UH{iFX)O+Z8$s+x+JkrQ3f3)0>*B=a-lGCMs^fXA9# zPm<^eQNDTb_OF)59{NK$d+Z5SGr>HMZDQ2;sJW$ET045^61%cEr%b!eCv{==_F8)W z2axUwD@!Igt)s7$n#{3HE7?jJG9eQ*6H0i%5EnNQ2ppZiPBN8JOG1QNg2 zzu*$r6azAOXUVP#SjP-l4BTV*?R1&>^YG+8&H+6eS80&QJ>Tj{U0$w|YXeG{+k7U` zshrPo3uZH;8o(}W40%*Pq|*2VI406yf2;YKZ_4GbI7Br3>e5l|-(Nm;Q`xz95}8w$K$6vBYFUTHE`jqi3gFI{$*KEL!`v zjKVK>{#}hV4y)~2X{;}2g!h$s@2$b&mFg62V(8{oodG1cLbJ}vOCcK^+N#tQQHxiwI!vu2Oh2{+ikTN( zBU_qGTs>^oLm=iETNH3ZZh@>joStw%; z)`rY#18Nxy_0rVTOoN-6%DTCt!de}Tz+0tQkDA3Af=aND8Xz=igK%o!(Ov}xDr;7Y zRU$xTmf7k7e&@G-P5$~X|Kuw((_bTh6@cpf-}ue)&Ub!|H6Qlga{&UFGZ});SO>-a zW#-U^8pO~JBN*ElSOjRKG*uhcyL+2UYXBABG1KoCA#*ug-~dO+fUQ>oSvO`q^HFf5R4A*=6<7;3q&U!siwf*t%0f?ouS zNCE*&vo(=5!-i@A20*JT3#QQ6pfo(NuMQNkuO$-1svyzVMU{OVhp(0+tdkMN2TBM~ z%iYnvlY1lBQPkf>uxLyH0jtT&47{@5DUq87g9Zcqcvc8R(24=fC4eH{8*ZCqm#{Bd z0IWe?WN@??$!{itMGs>1$jY`D;L5NdEJ#$z#>LvNG_cq6&UoxlJF9YAuj@fAE{q>g z?*^Ga#vjR2^ru6wKB#Q;&w72-X0Vuo;n4oTdM2jrG_)r2?LwCNFwZ%_;_D|&O@yGdEmOwO?S$E8y zdaPZCOuA0yXU5pyPTgR8X%aFsJ<7QP!ymYPqKsm8@-l;Gj1znV@ZbF0w9S10Mr|_! z$uR59tnZ!2|8CxeXAQ;+pl07q_sfpmx6sM-{K+p+nL|fTz#%hQ!RumgOzlVP^pS7^ba18ryu<@UX!;-@pTl^RGGD7Mp_O`G9bm~B_Fv3#biNBviH#aa@QN)%Q1N3 zGk+`>Pd}r{njoDtR@drxT+xOlN-h}Rkr10 zd0X15z(~-fCs%M08x`4o<2`cU+rEkN_`@IjeHpoUOih<4F^wO(_h$b{7M$AHQ%bL3 zk%}^2td;`#>%$&n-v}%x&oPwkz&vq@GHcG&T#r{T0|_bz_EpuZRkqBZYZi>ftvlNf zF(kBj4rJNF)UlcM?v}jU3M>XTIY~gGolD=&gG>$$pLsSZFY+^0&&l*`RHcCJR~c!l zgFs~lBMa$Cpd?|IBtJMd-fqawIR(@Tx_frsD24hW+wf>xzpb%~ZOF;&sP<(*BG;&S zyvp0X3V&>1ar2dL$~@;^5?6%&Bmp>(nnF@BJ3GOE2Id;-rfRx(w~0=MeJdEX2`pC0 z0C;97*$V8-xSaLZqE)rc9t&1Y6NT&HUaufAWT@R3Br$4m>N_mh%=U4GnXm=8_TTUT zlD(`7B|9WlZx0y{Kp8Srkj-M#M8+L~2Lf^hirxG@0L+<*5z3)jJNkG~*Vfl*ws&KV zjLy=+6eXn%r6wsB;R079P0eL#ZfTPO9n6GHz&pBn=(t!b>tq+3Tid0%rGsoEvd|lq zRR-|baL~UC0fWjN0JwG2!*!oJ@uGa_XMRLRMlQVym&&W-k`EoaS-$IgzF*qf+Ctq> zx@24~!fd^_$}s1(&?^l(RQ2mlv?Qv|GYv*UDF zbT?;bnZhA#2bb4Y#2SjoUQ}Zfb<2z4M?z$o>$83b!2((jK&}Nd8-y4zgU}2!7~BPE zY3r4qfgAY!h1p4MrvQoA+6s3_wp##`xIE9b#dZuxX5oGK8V!UzqYsb{S)tp#YptN4 zmsNIJjezVGmVHn9d8w=idy2AJU~M2J#&sa8JTZEf2`LZ1^v^kH*7x&rg*;efkZJN; zBo|=@)7;uAOY?Iwe)$xG^biy%?Y1ch2{)IKb2^J)V9X?TepLDMav5I=7X3Apec3<4 zvrZgkH8BvGTd-@r1N-4Z#PK5KpQ?7FtfWCxHD!L7FM@H!u7f;_k~ zCe&Fa1ebPm!8FH$T%2o6wOGw4TOZZcNq6rqx#8vqc|M*vdYFkEW#H-=aP7bK4RY5T z-^VlOnMeOZUU=%`Of)iVH>5xpY&yT9ZC1M}2G)7zfL#SJnI69=t7|L#`JRLKF(GjI z;&D2|0>r4%6UrPK8C)X?iv5E1jx}|xchqTG%kNE%4-;G=(SjrcJ}}-;Fu<)9HI-;P zfi=e3UGK|kDh6f4lm+vk8Lz?Fj`@Dz_P5Zf`3r~tgsp98$YM*y<0JjIF;uxEZ`dO& z_6TxGpOOrY*QKj>x7`2sZ<6l5ee&Gr|B5wsP&4UUCu=wPTj^<(CayvPC1q~xx;lII zaL*aPd{$lGjjiEz@>$l(J#YDEGy{70uRkIe&m7U9pRA%96&4$tq`h+|C7zJb)1V3S z%2>EiD&TTwDvL~xnI^H4QUbrvtz*tC9guQ621^(VL232+x4xf@_47}CQl9wq|KvC- z0Liy4vHdV^jOmbuv8RJS?$KR~lf6v$2K_(9p2;4{&H!-GZ{Yo-r=_>7a<>5 zy79fjdN(43a$(xuDVe(@w@7!}MW6H5h zr)2EX363v*Gt6(jfvAx1vyywaGP#-LT(Y-iz@necuJADVa5%$lOrQ+JI-=E^0mz|! zcTlZ>`ta~^rPzBr%;L2uE;r4lSN}H%7OURIRY1+A-$@3$P->#oY<_NB%FSKe^dXtT zLExF$&3T>bgP8_lTMc&}^XGpDHqokuMju7Z!gCX_gEifxG^?vJSzIqI;eFHQVPULd z8klU#QC(qTTq9V---ba3n7~y4yqX$mZt3J9>REhzAB!9tIO?O+{<|QnYfIF|T!RZdpsOq*F4(5tE9`aDGXFcVg|JfhQ@BQv?UC~+W)xWI1GIs#* z{;l8sopR4T_nCrRS6R&P#k#C$YNPIJu~mk$g|StJGKq_9m7)CZ>^z(fu#s#Hv~q4)?+Y$3SNx+}Nx#-W4t44Gu9 zsVv1}SraL>wX!ffC37>Qbe*(QO3!yULrCQ@LEfh8-;+xzn;3$>98k;zZoGbN_Kf#H zRvF1N1fSYENEsd7gCMJ|u-6=v0FYZwjh!cxMpxnbg4U9iny7AoK@J!X1R)q7l`Ux! zPU}z59J@ivZJknITi{qbvyYj;e0a6}C;gs-6{}H70WqIPZ5>-@AiIof#5IA1KQiON-NdPn;XU!B?XUdv*>4lO$yz783yP0i1y? zf9_ht7Xy6%4G&bDq>T3-0jf%EIglCSAUxmBzFjgfc!+g*H8mT2W@ys@c4KvE!RoQD zyf>tEh8l;a1`%GjWQI+~P~c_CA||zRCO-^wmiMfzsP@3CB_jm2$&I(YNt&BG<>d39 zmCF~7b50?T0{}R5!(DRkTmCm`@7y8Bk9 zE={dn($?O~pb^qjNEV^a0sFK2z&&*4ggFMl7~Tit2F7B~fqSK)+$NXKy&yAFmnoNo zDN9@D4uUoqvy2X(kdx0JmO`P4*N@rFq$vPysgdX1(J%bH%%DyYHDjSpR@t#MFy>xk z`w&$y>uYrOzUi)aNPFjiJaza_36A*KLvkv4ju~k~{J!CcpdirsXUrJ)hz$bcJMRBq z<(7Ni#eQ&)ed528)%Cd-K&cbZTV&N^g20*abiHV@wySS1#}n!Xm)-kPfYh>o=RtY! zT_2FM$DfqXfBKJPeI+_*tCO-wXWt&yCL@u9adQ6zmt1O+!5FJeb;_y3r~#Tp8KU=E z?FJ)Q4C~L$n=CfNbqwykL+*e3H}mg*^3Q);E}VHrl@VSaY>y^Qi^Z>9p`rsF$6edK zxyQz)MVx{Rn+JRc>r;t(bM{SKUI;}(?(F~oAOJ~3K~$jCL82=ic*Yn&WbK_6j|R5a zXH1Qo3*#6N7w1nsE%Vc(fpPT& zvEP4y=jk5CHRPoMac_%8I9fvv34ww_dyN5d2c&_iWHPlF*kdGFiw!L@wD&d{9XTy? za2Ma|+{+x?)nQP&nl0`5+GZB39$(u9i*ZIdkz6N(N!C|GfifCC- zSBsvLMQKFsR1qc(Ez;i6Bjs|LGS%9e4QWI##&R=RM{J{%u{Ja^h$XW~Ih?g!SzqHq zhRlvZZKWbJbF=c(KmI{Ee(Z&pHh$NCYs(RM;0t<%f(76e1c zzKUQJ1G5O}skO?Wv5h*Tf_3!QudZlcQmrF!XGxKkjy~z?*-gNRKyiHJGy}-BwPh0+ zSWR>|?5!6cfR9VyldPxj&_T{*#ra_D0JPwki31(-qqP+@JzkRK#d+;5X*~cn`gnYY8Q)8`3lhWj=VB)dA|QnYlR{ZIn=Pxk7rw^9hBW~rFa+lK6^xHs`>X7>uC_qc zfZr49%-A+z_5Ww@y`$v1t~1}$xvO&k8W|u02@(WAkRSnOF^VE3%aSG8vMkAAY-`3| zo;UXM3+uiA-}BhdVa8!BkL4s=vZ7@r<|u**j35aRIp@$o1L#KQw|?I~=iYN~RdrV* zP*f-_3P5+&tsBnSdw+X>``hO{b#;y^k&G$Ara=dU21#$&(F0pEYbDT=ifH>Kz+wV2 zq9gEp3HAX6P-X#00NdlDwGBj-Maxj9V9{Irq~hp*?}cIz@Xt0K)phmE6J3+wdXx&WSA|3xpZ>48i&nbhhqk+S-gr`g4}Xpp0sEewToRJ_ChiB+ zG^oj)U9+`50cuc*QP3S4I;S4{d5cyF+*#m1?w*SqPn7P?vUmbtfH zeZ-wSx=+21S6zFLjz>a;K=S1AeG-1_=$`9(W?$|$Z+KD(BdDXaX1uoU8v^PfaLt0n z6sW|aEk@Dh9**dGR^0G_D7bGt|84abYh#t;QElgtQ0G1a2} z-gwV1>ps2k*gv{G+g?@GFZ0~|@yp=EqQq+er6K8|s#{Z=z&4d!o`d>9qbfEw=*GK$ z*-e{unS1Ixf8~xbBOBUpShtLUX`e0%`iWzE)u(8C$f`(W7t;2Cpm-WpxRUs4h;LasCd6y0u(>6_O4$Nop<-vmsJ@>$v&K+?Sue&{9f`KBH(bt6p?N6087tK ziuk^g7@uPqu*gOeyP&#Om2H?8BA&-dorD%23J|{P=BedrNIe;lN$*Og67B7J821w= z=Mq~KKbHtRhKhMwIkzM(Nt<~KSE{1Fd)q7Oqql@~PzColClL{{yBiW&!3HPxE9yZH zg&JG?;d9>BCtxv3i1{j_6+mqK44@p})YY@V9oqMfty6oj6Gx7dRu(S3}LZY^vJgnX)Xsb|1F=9}JP&nnkaVVw@jjq17MnOb-N0$brw=}o8hK4#< zXkvcjm_uU(kXTn!y>#B4kTHH^>zC=LNE zhfM08Sx_TEjVyqP>8dC~D`VWji6a2T6G~QOGRGlENGkVHwT9CUjrv+~mZww&qS1P! zsJyej*eydt16tby^e55}sL;R^?yO(YhYIZT;K)J%?)O(x)d|_%Jk@kkhZ4as4^+eu zXlQcu7_$$sMP%jyumo%-pFU(XPKi)h?;)T`a~PqZx+(+NUdV$zL{*HhJXy(d#9(KGSl|7J9>DhJA3L_0(wGFVP}zM+ArppNcPu+Cg72~p^jv*uqVQ6g2^#>d>r2vZfwAC<)o$k8tK7l88{OV*ugZ_`QYEiz zhP&bRPr9Yo+@YV7>^TyW594EQ+uQ3ztA(n`dgGc&%I@0yk^;$-Pbk~1^xJp2RX2Uqz4C*viVBIZyW!4H$({ffVJZMh zsgOZ?Wnb;ux?alP&|8lm-sxU?>Pt!%nb?${+Z@2Us;a({-tM`<5FW8#a3q#zN(GjA)v^5|aGN_f{ssa{se+OeKTwBBFe1MKHuL)*LQ-d}ZF-hA4<@xpiHuY+1J zD4Fpu(B%=dB3WS35I59BnnXiQs#huC%JjTNmAClkaUfqdmmY(~q>s}sl=Vsi;`RqV zr}%E&!(Y()wC~8c!(c@+yE%=v%rL~sO1&}KXYs%7AfbMiIf}&18Vb!~-5}=1pJBdZ zW-sfZrR<-O?1}AON#k6>5A(pWe8R*I7AleRSQ5rF0mU}5Hmh0lu9CRpfjt}5 ze&sK2;yX5}Z?E8n|Cqn!(tt$`h^`Z*sAtv^Q65nvGj+4d$6{1^?=y=u{!pNUsh_7# zU`DEbQaPdB~LQA{qi{oGwfas&%X^?8uS;w z(`a2$X4^LibKYz^dJ)MMGBBAyjeryi(Dd0$REY%4n%bH5K}oSnq8R5)3_~>BQO(ZM zJhqx@(Ma3dQ97LFT3b7$j9Ob$<(R)n)e$Nx6~#INq_z&%+|(l4X>&`vdRGv}vFd{j zvE>C_Ar6-K*_kta?$7`958O*HK40l0{^|QBxdV*K`1mJ2=^b6V{z3pOb+sU>FgC90 zRG^;@QxH3bZ@wh=4$na-!m@28{)=>L)#^%33g ziReG!ZFa}=8DNW4Lcbp8gF3N#k2Qv-!O_#nehjo+-p@D@?i<%g&kHYrJ=MF0#wGz1 z_B&!B>~n-Bl-c#YIU&ImdKHuF_5dT#q?mMb`M_0Au&P?L_O9vklV<=WFrn#L$e7LK z2K(kIQTA)bs8CV7Oza58g3tp)6*{gc+Fi}w*8r4^&tzv`R4w(H=nRV`T4T`%la-l( z#VB~wu}cIJ3XZF*H3ydw3#f&{py0Y_zu3QXgV;0%+M>1LXHQzGaN>$VdOn`Il{=SA z712LL0|;Z;Lwi4%Rzgj@g^J;^gF8h(Wgn?u571ZNC~D-jH~*X}qM#)kFZb0dQT zZqA~W?$Dl1s%9@=bAKY*M3s{MLwXZeta-rg+x?c?^4b#$EU&!o9tCmxcfRR%ZhlGk z>B?*GR{zubr@yLWojHy0+DVP(xb*|SVPJ9B+X9Q%-|3O*6^;b*#k zo&i+6)zgZK86R8Y)*~Lowd{FwFR_)Y)_z!{GL9eF<<>p?_wMMyZGK57i#i#*Vvo0! z{mjM)ndFZD6)^+7z$beTxq-gkkQ(!#)T)j*-TfKYSZH(4KJs_zx~;0x^;2C%DVKN& z8mlGHvpX&%i86ph7i&8(*@uxW2-U63wdui>dnGmflnPFa(NJ)=ec(6TqN{FlySBWf zsv^kC;yP>OdKLGpUW9=&t1ucuZ4Go{UeV*eVOzz3g)XfL(UQ8nN_9gwd-WiWh0}D^AW? zau+QP=(rl~MqDe<7*SEfh^^53=`CZ%?&jLQ?16-q5woSl=6nX4ELG(r2e$hd`{Gm< zFXS2gIDGb^gGHk)prTgmI;YK7P{Gjc{kz{zGBodY88?_8a|qA_P-{a5en^=pW`w2L zwsgK?vLI7FM+q{7ErURENNh_`&CA%OG|iQmA5U#zQ$Yn`#u8amoMyO}%7WHZyF#H| z6jFesDiopa>JSS;>0_!uUj_NrzFhjAS;F?<6 zTt{b*DvMMYH728aTmz=ZMg}B;)7;YHnwwi(Yg?yls6*6%u^WwUd~8s491IE6R0(fr z1|0pOzVbvi6979ptWg?&^2dMR&Yb?~D2)p>By;D^bN}V{{&&a7jI(fDxbwr4%3-MrANV(Pk<7*@}Qgem|J@DMDE#SmpEVDb`?1`wXo^DrLRL4!FMF zgHqFzK!PF$Q;`e%s?>ESy&^$1v&xiB0VrXOvz~DVr+N=-ER3nt#a1PWNbDR_dHlksyZSLRGXTo4;qzs*Zj!3q&E>~N>Il2+h~o`-cHqOFA-n@ zOs3DgOg)2CY!2*sTYDWq3E)gb#6r*#f&}kqQxKPetcliMl5$AmV5`bN%Peo_2>0Y<4FO?b36Lm!;i* z>)B*YmU?AYT`oYfEP4(cgy1r|ZVTq4{ooTWTn~V2_WWgT?&51zA!1PdsgnmqIb=<; z*Op#$r@QW!kBQp-*81-&sX=m*3Lt`YRKx%gQ~;N)e!r^uJUc!|s|R3^d5mwr`iR^3 z%EKCuL4^`Kuw}zj?!>Wu`kobQe@4OQn=gG=#{*QtK%kHEw);QlUVi2)ZvXZ-w9Xcw zoLW^Srb0*8Ot)nD``qRYPq^)GuX8i!FVi4<>;P3x_R{`c8`LTS;{a+p%B&=n1_t`% zKQ-%FRS^qlJxcJ^SQ{0y`u0!gGjG259XC2Y>JzN#dd$Qz(Oyf|zs5;ZI=q*7)pS8V~TtSi?54$tH zw&J8uw11PBKYc&(%j`uf-Mt_AUBx#~fB*AJeh}MPKV@R!1Ln(Zy9vOee`f*;m2^oH zQ)v<|y&s&J?0Q3!66WYMkg!i7RP2{?K4xkzXCl*G_IG)kmiXJypI8dmd;38mX8w}v zw1%LdlHjp5XO-l{UxawrtF6*Q$V^6JQ4&JdW?{);qg+REagNqIVWKt&-i(EjII!hx zVApYh+{NxYA(H`d-ouap{#2dPjUQBgs$|opV%9=QB{! z0BRULs0+}}pn9kW$Wz%AXA>;8cAGHG;5p5Fs;g~qt(`MP=i&1>T4c=Cw>aX1d9SL5 z)8lvqmpJ~h;d8FP|CDQJD5zRPb&%%eItHQFRBQHPl|yoR*fk0e*1EQ~PS@1bq`pRk zZ|dn|#2$~K&dPnP(O3-xJrtnhU6SCDV&1KRf z`kBxEn!D@nd($47Bza-Mib?GId0QF;>}M(t8(5@DNFSmpph7*hKM}K0&te1=69rV% z^vDRJQrOxpkrpZdtSO|~5k67yQv_6k2QKXy<31KLvj8JTPY?jIFZz0qh(=DZ2hA<6 z+@;(b15gcnW-nGH2q6+GDpZLLsQKW~&|;MQC}VevmQhO0v?C>vsdp_#nJWdl z!q3C+@`07vW2;usBLzsI*HTpID#nWRyMwzonmX(-v|`J6XX#)D7DM&4?0TAn7F7;7 zCiJiT!>6CTu3jP_^A}&IL?Hq(0JH#_xQK;UtaUfv_p7eGW2W2u)>H2Fb^qp;uDnA& z;s+1@PX&C|BVX&5t-eR}KPZ0$<}22IP?bsm=1uqfvU_X&cir9{8{E=Wcd0#M>s!yL z>IZ;B5NG)f54ic4U+13r{@)n$r>aWHOezsj3SWBa%Wlv1R|V#%9zt)$FXFTB_~3sM z^?K7QkGjiOyiW?KP*J<4FK|m&zR$hz*catvNWcL6_>-gxLVKc8o;s#r5}>QNBzYP5 zQ8n{@zo74U>!t6>jv5;$*8>_D3^`!W{jq9)=ygkG*r?C*mizvLDq&kTJnde5;)`Mj zBy_|~z#L9&aZ)qDPa^x)1ct$ci3RQ5YR^ji{?TKDMR>;A@-C5`=Q zXx4M%+1Ln*a;PS4BS>#&CS8-;3)yS)XIx@Sq}QJ8C4aw3QlcbFPwTGD>)jLo{@-2y z*1>fngbX73!F^<3r-AK0RVYsrL8seAWR8tSAg z>JorOGp0y#(-2J-lI#=>)2Dk68x3T#)2ajrR`QK7z~hZDo#nNb;)@+s6(Q+%`` z9dx&LQ98A{PaChDb*)beL*suz9$=yOaKGLE!=-7uZY|5 z{hA5Jc#JB5KKXwD=Q#nwwvKMs+S(={$iE9sO%lDS8Xs}BwTN(3xrW9@si&GEDt%Vw zDEU*(-D*Z=BuP!8EOzkVe)p$;{DsF(zN4xm2+WRn2go^=T8CVqA~dR$nAKDbK){^;`a;IJH6R0Ug=?t+^!cd7nU+W-uX z!L#n@!5!}K{;k$RKy|OAqw^H6DFi3wuD1yACc#stj-yQoMHc!p0EMv=J2pM{+SybJR@5|uOma`JEqMR2&}=^IePsE|0(P&FscsCP5xTp{|XRqj1KU&-?tx8la1am%i~*FF8+zjV8|zox`Fwj4hV zJsdmC_!5$TQg5c!q^#-iAS<`FC$7+^f;ZX2#&xRrW~6qVYerS~uAluKJ>zG-|9Q9Z zl}9Z8O6IvnmH4Q>7a6Ol;+d+ohN`3`^HLUo(a%j>ka$dm1mZ}$v0`|rbzpp4tQzcs z<~#Yf5vBapzCL;>B7W&Ruk{XhEET zC=7pl_bdS-=p#6u5ENB(2?AGTOw;**#rR7zRHKw0f+NvbfglC%XSb0#Ot=1^Sa$Z6Yfl%JCX2fpV9c&8fPLiPC8SrVosL*`BN}1`I<)rWi1e z(9PgbzpL@m{G(*Gsai7Yu%=GI4I)EOgaTL;t*yP=wRg_+N{mzyZFnu!M0!;k3yrR& zwZk>Hw7RB3LA{HOjg9)Rp`PB&G5ri-928M&YN|BkSYWf7eg~8v)B7gHyy|LYD8mf6 z#~yvi{qq<9A!Cp$S{pxolPeSo?zeyE_uMttpe|^yYyg=Kv_*(UVk&V}(F@yHRnfqr z{tJH}q+ii0jy5U-1y57wt*I}#wvO3SLc|#!Kf2eQI(|@;F9Q{p^~>g!gI6rQuSwRR z8p>D(zyv{@R8*m^_ zQz@V_cM%)om0PK<%$R$HD1+?PeLLTDhxTnss`H9XJSes{s@(nds($6G0F~c?7%UPP zK_Ts#eT8c*Gz&CP89a09c(Kh3fvG=No@vjV%k}v)eaGC<{aa0N%Lm?JtWSENJn+kg z6Jf2FyT*J~k>gV3jKN^MU()OJ;4~MkaG$C80+eUYyHb>U-id-JvlLO9)J#D2AcX+) z;&aPNRYm>g&uRkrK77^>6{4jp@6^3!_8{XKB(Q|q_SmQrK2!r2Uv;wtVqSdmOK$J> z*R&?70$+2}M+AcLJB$dSj}hCx;PM*;LZGLzW>Mc}i2cenA2K!4s%rHyc682Cl4Ij* zkGa_kmbv*$R=e&Q3pBHjksJqhza^l3`PH|HDYJOlEn*`b-2JxOv;B1eR4VKEFU?gf zv`Ue+wR5^_Xlxbm;&&ufj_ltofJe)NC0dOp2c4DA@h9K{_0^{4Hk~EQ?2!X$A^AP!aT1&`*l%p38c+- z+nR~l72&!1UzFdpF+JIb-t3k_OQ(9gS({v&9p4hsZCx|m`yTj@dQLAs{zZ)>;j}qd zk^uCc^K3~1raivd;r4byJ{g`Rn@(zACI*qVtBU}X3V-H5*o(J5@Huz&b?;Y?@T1@S z6RkCyC2F>!ICYfYkAXv$RugUXhb7^xf*+JVjYzDXQ?wq`-#V^+p!1}a2#p4@sk}hY z_?Y=FuTr036vPPze;+3;q)d8OFa8_2mn04rE?p!0x#OJ|wI<3XF~lSpcM^#z6k63= zFGhf>?N+&GwkTEm{xhfitj_ZQi+;~&cURerMUqc^m#O*sUg2;{CIX*RNZwuiJN%<@ z#PVR#tV-#tC|cyv+x+I@CuGr}Ja$f-r_F;i08oVuJW(bkW%!r5k&{#oCcFJ1xXbX` zgBS&yePq}gX5F}EP(id{YPWlL-+EIb924c(7XjDdXy9^Y95JpYyaxEP_svH8;Ms(h&^x14T zf>O>GfChz)>?r{QnWE0_S)#;PxBs{UWJ1ZILfF{ItW2tj&FX1vsIQYMYCV07D5g?L ztgjV_q^ijKs4`0A2CC_}4Gaf->iqo-IDL-?-K?%tr~2Gq{>7iVeS7y94JVbG@I4p) zNvc{KDn_ZCa{TtpGf(|j>d)dgT>KbrvL#n!4HHn47%G#PHYQBAKf+vcs7janyas;np_*WjDY|EAOJ~3K~x?nCNmX1PzZ6x@f|$d=f=dSxG2MH(t76+-0e_iTMx$pw570Cdh}E7XHHgj#7$ts7KTcDpL)a~G|W zPeWOiSOI!63aj*l(u)NBSL}n@dOZt(-LWIP6_m1fp#DJx1~?kB%Z^V;dK0xS>r@>F zP|?Sa(2H0ARW(WkbWWe^-g%wA$Y;frf^U=bAo}3mo=d2Fr+<^LihzbClsnz^xBr5> z`uh7-F-6pd%4O*9P3&c*u}xw}^N!8@Be6!uw0W`!M-S~t=f7$Xx40EId_XfV*FExg zS`(of2Z-+Mp5tl%hm6h{*ij`aV@b=7zbEGlcuMW%j4cl$EItv2VA8!G|9#OupL_Hl z+*>a{XcgbdDpI*X!J>|0u&Ae+C~jIs+2Sy(m<5~79)tQ__%H9_&IB2V~}{icfp7UQSvX>V*4903Yj z&_9@mgi|F8ZH@ny?JItn$t(#LOKqz2%m}1lQIWY(J~huOG_t2cH}n(|6pRl0=J2Fq z;&F&ZLNF)IfRRxyF+WCgfK;t$?UzrQwXdS|h(FU?!mK?>nxHJArtRaaPcU z7!8@x`bIfYC}4oS=5`aT!GP&KjZG@apX+DF3|Y-;fk^^7s*7Zc$*vNRHaEA6iZePo zgyf=v_2!l~*U(rnkSKa-tyEBJs~O5#koXNssf~q#YicT}R}t0Jx;iMvTsM7k(B#G> z@o&SMy)lkdw*sH#olS4M<0nvSH9!bu3aN5>U6UnZ)Oi_SDZ)z4b12)RWr!*TnK2;L z{qxT_sMDo>J`3b71&|CeykFZkld?g<2kT1bjV&8B`WlG+`PH- zlY5{nsG&wb0N5*_`hSm(B6x(5&5+igfFS=#&?ZzCy|4}MQ}5!SW0vBOD(mA~YY0}< z)i=35#$p`b=lc74ZJwcMSEYqJ>{h208?wKmI-!U;YmvYdYyM2%2@|6jIIUx*dEYoJ z^ZPE%cNe+;ciXI&1B>RPtSV9Ev(c))*EWc<1OTC5kv?JeHG#VlM)d{V2dX>+1E-TL zX`n^1rxc)2DN}!rU(5-@Dq&kEvz29ntPEI`w7m6MlO*FA5jX@1b&D5$J=q6W2orVB zxJ)49%;{t9$iA%-#Ib~$2a6?~`Q%_RA6|xQj%pIQYsyy^ZM&4NB*sQTijp%HsxqWe z5gPVAD&xvI~Y+vPR29pPbY|sgUs}pbH9_61M*B4NWcX z%4_a+*WdOD^_su@%vasp>mPLI2G1(FX^+KhC%%R2hR(_y#6x>gI3HDyCcq!RMk0YZ zXIHMeODd%FDV{ubKz;@P1O*Mi*VNXf(H61_^iebJW{kPN_41jb?%_{q3pvL?^AXz@ zv|h|y=oT%#(bd$~yG^e?rYZu@hihUylxYrxCy?HkY`hWEfvY5pL1Kq>O@HO(D{dEX zeEqp^xub`+B}$8StIONCV43n@k$cDZkX!Hjb-e|#pj}(miz-L5*4&mq!-~LSy7u!4 zZ_6pt8q(t0r_E8|oQ!bsm97O>tZ_Hq`AbS3p!TX*WPDuo+wPeQl?*s?kU6ceglLB; z=M?RnqqCX3&8W;)m>evoG*M!NwReA7ioJWbz2YAK)_?O=#Z<|&(jAxFdw<_m8B6H> zp{i&~y4XG?{u#lBxEh53FX&iX%lbqxanO?VFvMVY)i$U=z|Ylg8bqtEv%WfqQb|*nSlvuqn{pIVSrb+mXB`DngZem_Fvg z7BfZ)LCqukw~CeYqw$*D%l%NUBPq6|=QlA}oZu`oU@jVDYGr#10@x_Z08XFhI(z0T zyRdJ^236Ez0~c?LaNJ_BXbsEpOM&F1hI^7*?H9TY#;#Woqd90AB5wh_0YIbHVKB(3 zLsKzYY6^mEt^2T1V+uwE?g)tKN5o(&$dDo#hQ#Km@h46yaP6UfSndt}12}J~z%ozAD12EbHgQgq?6Bffo^9fgqxBKT znicQRiI8PoyIjK}EG z&~(&nsRA*pkCueMHjuxVAi+>JM$j+98nGeHMYJ|Qa60iRq621qhz0*1To$Lc^(~_8 zb@Zrr6x%C*Fgm8-lo1mAX;j)EW^-PK#I7jXGfBoh3dR!ZZM?Sx5Z~3$I+O zu?bZEsOnLvwu|C^)wo4ht#LQr^;uO7-+tv`Q6o{~RVB^a-r&ze40)D7ysy z!~_YwKHTr5f*aQsb9qOffaV$8e*bSu1r<@A=O6zkqbx@v9Yx?FN43vZ@O*;6kK;ku z&ipD>F9Z3SL0Ma?5dtuyhG9nGpBtJbumcVC>F@jxi5!KVYO2tHWa$6I4}8Apdy`F> zkKDAdE*V&~%BRs7S%dd{^mko*=PbAGkuQk)tOP>^WzEuO9TAy)&z)a*5o5wCtj64` zmkri@ToQL0g=7>|=6MTz`?-Snd45MsNn93~6e&}xl$D!G;^5NyG*ponU3rt3YKTbn zoj8>J!jfRo=2ZePDNOVp*=uoNZN2E{Fx+6sNG<(BVtDJp5Ie7D4t?~k?(n`XN*cYV zUp^kJgk?GP>$o@oG>&6rTjniVbzXIpJXkdU69#VjOl>t8^%?<1C>{j=GD3rA)4``X z^Aa3V9xUqL$(*CeB21PopXg3U&VmhLeG5Y#pq*5P(wvm12a+wRtyf&W39HPsziXO%|5PHjMFltDF7u>+W8P|9Gpnk{8#$42^iU^g1krybU z^4`%=nuEurl3E8!92++JX;YJHYHC)+v8j=P=qNT02vFA6QWd0Hgj9078$Nf&dLTUD zR%KQH2$V`cq}y9~j4F-_XUDa0|7~4ioNWY$IW?-X>7e!W5l;dZ!z|6%*~hE@ykflb z0E>xn_4FPuubxS)={>&s9t?{=Z~AIQUG{-`8qB4FHkzrZehTZEp!kIE8X7w11^|mg z1{SSX(JG4r&`v#Q9P+aip{Ul@H@S8N5$$exXwaQFy5F7hN`j(93IzF}P8p9F>xI3e zs9Q8@dSM8@`5dZ@P*F&vgi!#^)Z+JAmu3T(nd?(noZ!iS5?UtExo@g{nwDA%0DLxWnf}JB5Bqc7OY(7u<=XyVaU8%oruJA{J0!x4reO1a36@IDpC$R-tU@lv80O(b?Iv zz+JuiJ_WOkv%n8oYR8nN1GUsUrrh!hmMgUY*j*C1Yw!Fex9X;kxMPQRxM#lic_mGP z-40JM0gIWKCR?*h{^jjEK9lMV07Q%?&zix9&RVcsNnUI|_Z4OrYSnWWtZ-}Y{6+WX z`tQ59)<2|p$DUuCYwwz^xsQna8RN=)P0_I;nwfjT;TlziZfsJ*#S$ejs~WUN*b`yRin2;& z5s|?m{A<6~QIasPq_SAf#=lF>j~?Z@3s;FLz*rKlA>*UV+yE0n?7nl01-mqYM{O$S z`jsTYHd#`b7|xQW-aLdLqT(y#{<8mJOOS|R9h>U!WYzzQzv7a<@lt@ri*?M42o|GI zEppDq6q+i@-#0cks}G^C_ps|bbyy%WgnQ}5r2$~<45c`wsvg;O-vmBcpjZi&BYF>D zgzuq3$EN265Y(_@As(7`0V_2!s+>z($4uA9Of+a>zN!W`BTU%W0VM z(9-43_MLRcj_&dOiHH{&-8$1Z6{1fyW{cwEE&8;3W(v} zCCN*FtnxrH^*c%bn9o=@HFdbz3s<_%X>&XkaZG)*hxc!By+`&KeNxXL4o))Jk}0j7 zP(jP=sc?j3Ah;zGVrUY82KT?Np;03(7A(2m9Y4CqZGH1;fgjxuzh0nWi7rY4 z7lD&K+h0r0H3g?m&k$b$9h%vSt!+K-#IZf1mzwf5LHv-LHUDZUq(Ut_w0AR{33u+y zDfyl7N|uwv+>CN>zSAm-Vvz6;uNbbeOJk!-X3kxFjazud8c|-izWI!VS&Umi(qu}v z+1s1+L)(Bq()h~Tw=-nvL2UDXExpYKKMELwih1% zqTBQuDzT=59O9WI-YEeLVi1<>1Fg?$*;5k8B!TH!=6JA~rp;XB7B9P5B2?T{>;?Oe zL_G@XozrHyr@#9*ZtsrQbq`^Cw06#LgZ*bzX-wLL;(4jLO6`SI5sRNz3D_3fNB@9X zXY|kB{|o=O!^XVyuZ_v!kDNws-l3_t?e_Yr_#3ZZ9*hdQz0Sq z;})}2yW!yhUswpS^F-%+{uSCOU+@GU2s1&|i+pH@+rR6rq&*~6oQ)0;?G066YwBJ5 zwAs@8fDTR1Ch@ach+;)yUu-h-6gj1dia}DJwbm=xS+E`W4ia7y+xm-nhc4_`7n)!x z_3alQEZSNuQ(4TLr%5*4gkaGNz%;jsjzsh6iDP?{04GtJ@*6vGdJ!0uN~mY_OD(Vx zvcnX?q5vsIpoYG?D$%9@6=cEzV1Y(O19LrngHXlBMtlWqFmZMv5ERWSn&*`|g>eIP z^#xxcGpC_`rTT*Cc>p}JH#F%FNnKJf(>pB&pm#_<{LIP2x-WomDmH)5&^zA zyn+7Hs^T!85rGMQ*4WspY%O!B>ZN8{E8!ff0s?0vL$0Z<-8B_jHAk_o7IBk;t8yc5 zXyBx)hMHQ3;$ywdVr*#8XpOqMy5v8UQ6G@%7>*4a(rz*4bOw>2(yUAh+ z5C+iY={kTTj-gQyNi%z#TF8S6Tf5vtKsx0$3G4)?d>+muvq2|tNI`(af_YnCRv`~` zM61Fi)UwdEqH_x5pKv`?q%DXFRINgDn~brluwL{;6-7@E1ndD4H7-LV8>~-JfH8o> zbH2I=NE{lL&<$X6bPPIihih){aW!=XRfY~9*r~aA2rnszpE`fe!GfE>F_W-La28$)mcQR(i6u_cVKu|WBbv0|D>>1MN1l{hd5`@IEfG+XUhC=20nAyFfMc{!{MYzIPJqwk% zY;J?5K2rm`dEWRhdgMhz^nYXzeo1SxnR5>O~c$9krk#C_5g|Q-3EfKUKC{`bC$SNu^>i6Cx)u6Ce zc|Ua7+wT8OH*d)*xA~2yG=7A>-5{1zl<29XisW+<__OJ=7AxV_-*-Yb8T*3h5LDp0 zx_T1|JAObb24Fe&vK5LKSjQV*ea!9Nx?XK6w2Abe?Q>^N9Z5!WMUW=BgPA1Q1yD}U z7c3H^thw`3?z&q(t~m0cul&DK_O-t4^H0*m=aa1e5;3GDGA!X6Kp@W{v=K=Go^_+P z8U(N`scnAQ#)qXUcDcKdi6wsc9*%2ezd>ckmhai|x;uGvZ<5@f5G+zNtf|q6oaXj! zX-pt!Lji_Zl^Mz7QaFz)$KLK3OD~F(%I;s!L>M1ef`@)`gtADATxeJ~C8PZwdvgXX zR$@lArf221s@^T*3{N58F+e~jvw0TOZUXSINKl@ z?PoA1G)4PTow^@6VHO5J1}Llcr7u z)uXo7C4*O zn&qHstXgPUR-+pkRh9c}L9{BqzVE}A79)DpKE!lwS*Z zJD#k>3N`|U5>XRCt?CE#ssvCwlit=wNh_68CcYV$R!K& zHs1FE^8Bez5Wqqwrw^6BR-Sh%KVRmqO#v)sj}Wbr2rS0nFbO;++q&Le@LaHa8bUn_ zF$V14xJI22j4)486<+lR=j7RQ74XTva>6xK%D0q~64AD^J}P?S7=Hoq+y3@C*L!?_ zTE!Y46KiGp4G*|gH-ALn_l@Vju`9gm z%4_ZttrB6U%U8V5J@?o@h(*KDb@mTHy|ukZ;Pt8R{FOU>^6(VvUEXJewW0(^wVOSE zxm&XQRw=gArw9;Es{Z~VC3~)H?%ZN01IFg}SFHV@D5$4S9#VfGs-u~`kl%lm1a}_L zOLS@GLhUnrJ760?clSON3=eBP34)#nAR z8eakcCy-CCKYPJhV(f*i@c6T(NvKIHh6z8ro;ge1Jso(cmGfkjU#OitYQ z9uPRrzU*olH4Kv|hW^1zhInL10MHUQWb}-d!q4D^Fv|_2j>hd)iX!1)j_2@d*-C;BU6U~2=jP?M0TLaYVf>elrZS1 z0TTG1={u_Hqaw+7koy zMmTZ$D~-BiPD_AAv#yXYHU&bmJQB32Z_;=ZXruEMuX0Vzo$kn?ZEoQ73H38VVPW24 z{~7v>hTSN=iB-sCJL~~9!K($Z8kZ5k z;>f5Q9swv?Wl?>JqMD`(s0JkIRjPAM?K50sp;Nyj;`72S7QNC(FPF?SbVz9{Hp@s+5 zQ|y@%Mm}-Ed@cm1G>6JRUxGFOqh@p^$+R&0E7y;4DJzS9J!Tw79xQq~G)XJ^;OKj% z+5z>HYf!^%QAl6GqbRB@`puA3U2`iWS6Pg|A@9TN&~{#Fa%N1)B<%0Zc}q3!0ej4g ziUEQr#{i0h12!VVO8mJCnX0A8emn-Y3F9EK13q9)DiD@z;Mrgkx@IhJOP1X%f4Obr zvr5WJOv5fx|1oQE%^jaqYsjY89#^G{ATGH0AifbQ+l&dh=H`#cAH4L$m&7bsxa=k= z8ov6>*WKE?Kci6>fM}F`S?A9__&4$^B!?OM!puGtWI20)-pS+pG?$Yq9zE;~rAH`- z`@ZImPe}zBAHVvxPq?>Uen=|e$o3!D^_IpX%$T!OJ$Da%nX7$ld0{v8DH@ui#yu$KN)~r|fsr@VTqp_C}$^p0mY+icm%WlJq-<9yjgo&Pt zz@k;H_>UwM_m=yBPwSa;g}du#|Fhe@`6ajhnXjnzqOG$>_L>=%ORm1nt$*fU-Of$V zi)q9B%4=`=nA`T&4+N4?=st7iggeVUhyZoGO5^)*F>Q3P63KT(`&^Z}ni_Y*Z9nf; z-~J1#mOk>0|1atN3`w-afkY=ZHL&O@cVW(Ac)l@MlL;u*m0|1? z2_oVzDf1J5iFR%Rh#5PI2vcK=8$@M08MBstNeq$#TWii`%T>T3IjKa)Pr$1@ShR~j zpY@|eRw!r{fyIo#4Ju^>us&NFdIcxD@e!B|ipX4=kV}=6K&@Y}bnxU8#S@-=0F*3j zz*6X$U~qO#J*uCr3fPzlg)BO~g=8I7eJiwBwFg?Br;qVv7!DRL7sTeE?9S&nZyX|< zrnO_H959(z%RnJQVk)I|4Je*=$^rBq-IoT~A;77!K2Vg)$mSBr0HirjKq%FVpty=i z4nX|O$s@`bs+UruJ}f8#sGwF$_K4?o_yF_5&bX>-dLW0~$Z)?KVq?28RRtN30qxYP ziUBM}f7aLeks2+kOj3!IVyYLtpwXLtMqYM~tTk(-r{d^6xN)TYOe0lRB4Va(gv!8T zsP&uZ1tgvC13+hDP7)>Zqji$?uJ_wr%vAd-1&ftb z5p#DcNw}4)E?U5339%k!cd2L)>>oR_%fvwdim`pJF!31tM>rkZ{{bwSpU8j$GZ@}U zmdJ`Gp40vksQu=0?EOkk*4DeOo&|39f~(d0#qU_}tmFMVHpqXa;zOmD)rEt_{83|2 znzC1dMX~Fqr*P@DcWZF{-tBL=o$tJ0N`s#IhAkl>2pFUPXy=yo?v-c0qDmUA39_cS z{$pAbmMptXRXzIHp8WP->RyoaU3T=dQi^BMOoMS<`1PQIhkOr~lQ>zv2cl zRuG9nlxF6h;N4>#ZYD{jg1+canL*@wQM1WHCA$FJ6jt4(=08ms}0a!x&SUDM}UymaoYD*LzG z^DFMauD9L#XTB_vDN|z~b2r`d%j!2@|MZvLnUhDgU!e}KSo1-F_ZJ`kCxLv{J(XQp zE6Ooc6n17o^ZA9UG5F46EKJw**^Au0ANgI^J#&$Jqt3Gm6-y7VsQYp9jo-*?xAVGBt7Tz2JJ6(*=U zAKAA}aa#VBXK^ISe_3ps8;p&C(%RKCUzKors9~2G1Ld&C1IEZA)?qF$fKpQla=<4} zD!|ZT%|ey$>pkdB9Y6T)-l&WCZBwlXUW%km%7DxHSDry$4OJAWsVWJ@n<5vG1VBgz z0rbzwkRc?%0O+u=a4^swF?I^zMROaGEPrD|lgbEv*I`0bbU7Vd4NNErm=!|3>|dbJIDEjmr6jK-!c$p<6N%!?Ms}n6S;4>(V9~ z867lPZmyaBLn&$*Ws;wfVWoc~p)x=(92<4bEnT7rK#3h09MnC8hAMFzH*P(D8ksPv z%(19o@#bZ0M{TX^p0Q9=7BZBB1AW?Ti1t8sU5yWHd4FwfwZI>h#RkA)y;T$W z54vh&1C`1;*VZvjvlpo~^Eooe0*Z}I`mE+wLLZTxCqw6{xxUnAR1gmsJ;+Glq2DD_ zi91;jR9RVPyjWX+(@X$g>7t2)_V5`G_V3Wl!$C=d8|{>Hv5KO7kIvPo00QD&(-%k1UN_1(fuiIIQ!fPY55vj7WOD z=x0P7^`$5NMIt?-{`-Ey1S~4MTqOW?_395uxQ1u?+#`Q4JJ8iL&)xB%-xkQ5xA+>j zWy90%^%uUSd5t85p<0s2edmqG)!VuD&QGfn`Sf@HN=f6pKKwgw7kjtc=xB> z4e$F!*L!@Qd+00wk2`u`M>+~828+4xomyovfJNF>eD8Q_B)t8xbG6ZDrVoLDi&#=x zJEa4ZVEcbmz#^391y|gl`@o2rAd;20)HwN5jBG z6;ld#@o2Q{gB43|bX0{C)-npi^hp1xzT!eb#cbtEaIr~(IKPjIMrTZFyh@y14lLT2 zC9cf=R#Pkaahw@F9{?uFZua1cHve}}d`J6eKJQTKYj2Lr{qe11TkE=1*<~>t68c~IntRaJ8M+VPnJV~Lo zLyhxfxD1Fxc?HCtRh1UnXK;pq%eMAuu6^1(S2aE+XM@pWpy|Pc*%UlEnmKtF9Pcre-E+B&+WhRS~enF!rzj7W>XCNG}9s0h9pJXBiZ#%X>> z_Q{4Vhq;RJ>dFOY69l8GF8aBa%&AmWv*O@2u2Xxn?*T6Nieo2(%15Ahda;PAY8kOMsUoMCgn1&Q$mz%(pYYWPK67SJ8t+#BGAG4fImhW$0Bz zpawA;=%{1k)vms&Q|sPU)w+`>pbzeGr%oPqqn^HMRZsiQ@I9$vtJW9{t-nI6o+&DY z1gchTw-iPCl)UGU%tPK*Tmt*|E+4XV&M#|(6N9R<{h{eMU|VoXqA8+;!z~0sF+#%M!yoR z-94ANg-h4y@2~#gYZ^NdguX&(E@3SBM5E&(aJ6F1{chI0tE8&B?xDX`a0a-0|HuC~ z?Qxhl%(#1N{e$kBn|{_^v-ZR4<%e1d4H6r$=FVTzp!+Ak^XIbVANa)o>0W#8o2o`~ z&WN!*^}WAxSFXHMqGvBZ^ED}Xu2}macl_{fxA~1HTuW=WTfXLl?vbzmp@L41`PeuA zSjh>ic4PrY)+@xd8(T>v;#jxzcTzRo{Kk`Nb%`NMHiEGmUoI7(3N!=S73VC~OvP!l z7Q5G<|2Os3QGHbcI0lPhPv!Sz=I3Qo1nCt^iIXH`wVN^b3O#FDTLAS+zPoYPGjoaC zyXy`2+{1sTYhcKF=k&Rv#?M-Cm3#B$?`!@eEd)Go6w?uonM&1bq7=&HyCA;K?6-1U zM5f;V@!xmTXD)WHtoyoq@rf_GQQ9_=N>~0F=g+)c2prBVuHbqft(J+D#gVY){PPks ziy79{RZ6Uf*vcxM#TB@)o{H~N>Gw{4&o13Nw3g;wskKbv0I+CrYxJFYd+TG9%r5b2 z$5gA?!!QAf@x_v=MsH)9+PRoI!0(cKS5h!6d!J;h#>T{qqu6n1?>m|vklm^8y?Z-> zC-Of2y?M^(J!f&EWm?j_Rn^FNQLVEf#$!_YG~iV&bx$%g^hDUAG?0=QS6fA8o6Ir+ z$z(xMpnnl`S5=87DuEbAToBq)_3};k005{iEOs^l;1Q<~h78*r9jJwNJ)z>FUM$U- zv^hJB4uSRo5GLD*Qz2`ILnlKYDwYTes0vwCCAurYH@#k>=^7_QFX)s61UP19E~0A6 zzmezWeb6(I69$X|w5SqsJSlh8H@W#sR_Pe0`;Mtcv3u4c(H-~gd_xMb1Pkhe^dl<( ziTqvarXDZ?8UcQ)E;bf4f3dpCXs3+=jx{E9Q(vcQB0#O7(4-0@f2Wd3FabDM(c51e zjvUG>6kYx#5QWA-l?otLBz=gUxhLx$CaNz#BO1i1lxh5i%P7|&k)ls=JR6&xIvt%(2*Q#p6*@r@~{8kaFf zMG=7;DvE$b>sJIM4y!+L*wsKgZSHdQg$`98=}S0vm?7IIrFaT`)vAgHM8nz^2oz1F z(M_AN$W5DhndI^5u|3^)RC^?3VYHUx_`fLBE>0|6Iv4ov9JyTB6Ch#f@UM6sT8^x^ zsW!`~@M8z^3AziaEM`OI*tQ1hHd%F?|FqeQ^d~^^=%F2|P$WV{KB*C}{V6>GZ^tud zlYm7(qcjt{cqm=6vN-WKQ&FUX*4j2L2@u)W2Y0>gjvv{R_U9&GaU$qY`Ber`Sd^Vl zsIpe&vU^Ypq}tEsExOiSdF|cqo!1^y{~y9-&CMNRjX))%PnV$}cQm{Q|3BR8>;BDc-teRpS?QyE{;_{>*WCDF zfy@JYHo28+J}6KM2;IH)WjAlpN_WjoA8`+V?GIgh*GyF_AOF^$iB@SOl!?HiJ&(A; z)H!XQyK>dtYT;0yA{5c7`hwW5N$J|@I&ZrB)1tN>-uI4s`g?!vjvd@?Gf~4_$5NH2 zvN1~q)`{??y&tKatv0``x5eIZG$JyG^qnFa#j8f8!7i6FF??B%lSDSJ=ftvg)#qp^A73ogIj zwRg;LM-FZiZM;ZGG6su&^i9!s_>jH5bB1DG3M!WDwvk@MtaXjest9I)m0wt7&{KggmIR)243@bn9>S_@Xsr3Ro^~oS zl2NU=Ck;(4a_IaVZ~+LUZw3B#NXh_0IZwoTpbYVP&>kz}2{@3LKvbg?c#YqiAe)gG2qw(1urH1d5EZRgCj58xq^8K0oL; znuin(77yWAh|5a1g7M62bf2k|axB&`_qsUXV+{}_)FgddW)K2>Fr25+m$*(|$($x% zg|vB-_8<(1nz&2?96g{6zsrxyV64W-uu)L~i&P2ei*0J1?y74G8moekP4DqTPJ%g} zx@tl>M)lxj^515RslG7F3%VZb6X6elLJ)W;2Nv_sWU5ZRa)CSushq=>&~1$A&^1Bb9iJ>ppHZnHVFW@(51J=ONZObW85ba?PZcFgDlbP5?bNerX`iMw4wVx?AN(qD1k_)~lcaw3-3_-B z`zW>eYW2e2L$BhD1@7f%=vDk@ON9HXX_=ckC77EBi>efBma~6mIrf~GM1>Z`Xb8b2 z!bM@^Lt>wc&+gp=;1w?5+}kX^Y;}vSyh-sL^lSu$(gl$NyFvS*bigF2N4wL&K%c6L z(p(s2{MM){{6WBy*ugqa?G^8qQYCpiwV3ABSlP6D53gT@t#vbnahU@^_{*WBDLM{xS&F^Ryak4%-GAV6nAGE^d= z;?&k7FjJ#!)L{Q<(LY0fqBaop!LebL=tajIcdDr2%n2F-7$u{HVw6eo8zq)1qVepl z2QC>yF+QfDy{d5OxHd-;hav%%iKnN(F-KV3%FI?hI#c`Chut5oR($clC>%NF$@M#^bC zM<~c-=GER8`d59Wk+mZ5$4C+D&e=SMJ2 z7J5WUA1{Av8#&F?R{&5hiZy$W93;DH{78}L-12L4qTnGLUPi}KTpQGvA0WUY#gE60>P+R%PP&(cPjEX$>n8678H)!B!Ftgg`6}4(xk8I11~? z?_CQH{oV3FuQFypKG@~Jrp1qt3cYfyY3w*_80zN1J@06i-{`2#&@KPE#9&ePFU>h; zPR2VK?#SFl*QiPdCG_y#&90`d&Mms~Mt8&eKIz)KW=p)~)gOFa*G$3|`%fza_FnyN zHFffHFkfJsASN>~a9V7XwvHKY<&7T}O&6d^Tf{3r_?kpf*536gw`=oDZtGjm3hZ&* zSJ!=0B3DUn*2jw{jX}3v4QTfht5B(shzcUm_}Z}Xsgwc6R=n!@kaa#6Nnfp zB#VoZ0cEME?=JYBd>zN{K%{A0B3SGZSZyR4unQ96i(gS?v8Wf9_l1!@HKvVm^29;i zFWL8K99)QrG%Ah6dIc|@7x69ZIBdh={hM9?8Afu2dz-IR`&NjbuvnymTUqg2E(uu7 ze|!AcBnl%#R#2n*p}m{k$Z+TtuusM`E9(pN)fVqKLr7ml_bLMxL%CWNp}Iz8O95ys zEXv=a%_+{cp~iqkD2mo&z~~3-O_WfHH?Rc%1ndmkh9(Ielu)0+wxc8G46r3aB@Lz+ z*fB!}kYFB03O#saT6wdS>jdUZfh`y;&It-?UoXbpjG5gelNYATnIH9>Q30mng?g#)u@f*2GZU#WQZe*Z zLj#HiB5QqBk>549b_iSoEcvWhz+)o{9FRFi^oHu9nv>-q0Mw=s%QN$KCv^@<@ECp* z=x6E5D;G2az%(4a*1j(|gd$LwQ%X&$BZ;s}aImS0YoOa@)+OUIkcZaz6YJj#4hgkD zp1TaFrx6BHrp;=C25f*7g9=b%&Ee3cN*YGC_`XH@6w{FzBL*Jze)~J%u+Tc)H8MYO zWX$#U9&*Qz?2~|#L~*2`YQ2t9VGZAZ_Ho=z8&FQV+1eDeHJ-62H?Gq?kgEoT5m<|@m@n1-$Spee`J4seQ zCZ)yJBRv_}vHC^{zVysmqU4WyyhnyrX#vPU&&)32a#hL-F0#y9;>u#_s-o^rV60h75XpWgW?H)GD_ZqJri+)K}VS!#v=`XFU5HNwVbiA=P0 z&5{~8V34l^Kw+Eu&-UuMcTSrt;S>BK)w1mypA)+Ph0Q(NUQrJupc2Q1qA323%AKhG zs3F$Ws-KcSHAueqkOELfVNrGDyXGyvR=?w!Q}M%JojP$qi7w6yZ2;y5&Rev~U4Q$} zyNAE}hw7)|dhjJs;Y))>+cT^gs#Nqy^8H)id`4`DL~T3G@K*RhZJj9&Xzp-p?)sEl zcI|!c$o|dl*@wR%`l;FlCQ}rx$WE3@T!zHrxTv`#0oacuoB3WUz*KtyuA5$cM4+9@ zBMClcEwi|lAn^$ri+9G7xtv*b;Rxyar7vHw*Gf(WN4UnP~O;ojU3muhG=jrHvqpWTs7!d-ht}?|@Xe42j2NgOCg2pA%L&h=C z9l6e70IC#N8`Wey*x#1~W$^V4*i<#MSwlL-40fPoXR3jLPG6%674r4iG3e^d*0a$?x$iBRy-h(6 zed79`vPQmY?d@`yn`Kq_Q3ViM=e{Q_h?z*GvC5KF*ubPMz%vo7C>hW5^moPwaL_4d z%)Z>sn733uhVvjfb?neC_2+P1nUNp$t#Pc5?3Lp$^6d8vH2{$fyFR?HL5BJ zpxeLaE?nuBUw^;m5<=~Vriq9N8TS_+`zH;vXOEkBjkQVu>;nS;|5Rx0)VK>;0GivT zyBV{WSVB+pjvLkYc&6{TDsmi`*Nu1ovgnKeNUOx+PlJ7CB$6>h%-=Ci3YJK1GXD{# zPF-z-l)VAFEp5}?rq>>IySBV!=PP=Dnjl5YV#W3MyY5*F-NRq`ukP$=8>3Z~jQlF~ zJZv;md&f+T0pT4eu_Cn}s@R6RL#4ZdedC`;cz#!1`+j%JeZQh}e)ggN>2_>-!2=o? zNaIQ}m+hjf$WE5#Q*mGM{ZwTUFG7Wy`^&Su^Mk*ozPleh_%~Y5051Fu@6of!^}qrK z;!`xV!PLPpcRHk+1!cM!ket(%Rw?_b1N{B#%wa89KamuB-nHPB6 zkd#6<165)QI{S9M>5d-QX4X$_VdR4<*dK`hS#%^NWD?#aDaI z-1HE}Ow17$UzlC)!~9r8s)#qSJt3YBw;^A%zQEh_6aVpd6)Y+s_B|muYXf0W z9#B0ky|tlDCUfe1KVa4Yd|BP7Qx?n+7zaRzqYFTm${hWS zhNs#(LIhNN;P7)lsKm8*%~6JiHRqgC~7==}% zOa{+-fI+Wg3V@p1yKUy8<}?DfI{mQuvjzys?ABSvzYeNu4XUH2m?{-jsi6XN#?`NA zLOHdrn$LR4YvZ4r08Z!^FlwXq2oj)Df!0V0i^2VxDbZ&V)8OJQ?kl&UZx-rY60{|; zWRj{#9Fazwc;&6cIYl$IOwBb=NPYaKK$z$0$EJ9&s8grfSPvz4JQ<4-3|mrNkWn4A zIf_ZIs(n@nrhs;BCW9WfCbjp$G? zX?>J{QC?6E0SRPM>1RSI7fN)Xg}=AJVllk`(YEj&NQFwe@p_7SW5Yh45?BmXl*F?J zh?`5Ac=|I82C7sr5l;6WRUa7?r5I3!>UgQ3Sd{=z#|z4hNpQ+Jcu}Yz++_3v8_&UU zVM$g;{J>&3POv}8b?2Ukd65__re~1gkMVI;7O%ek18(2;H{9&YmW#4U zpV13Xd@%uDneX)dV0P_d4okeQ~X)iw0Z9E!L4p|Xi)LS(rfN?D^`EN zt^dK-)N9%~eZCkxTsMhwEBqK0TdxTcO&6B#n%DvtfknTl*%yFYs*21GeRKWy-80|& zyy-khC@8j9fz^_yr52xgX>c0d1Fth-evr18xLRgOF6@g9mmkz~9#?|Z1Ix0s`%8Hj zFOHWBF;3Tv%iO$0*Xa6oyz@dbjzVBj?J;$J$&{jer%6o{{i}0x7A)7S<a~V8Z_KTqzAn`rc=y0!-hbfW z0WCiJJ5d(MG7;Xmg?(M3kz}&%h!YIKhn#d$MmJFd3ZAK$?UA2G2>vfpdk5 zL*|7AN|goh$;?DGghMZ_skNDq9waD`6aBTp)mGPv!UrJK$dEedur|1zO@-42Xd+%? z^XU-XLBQseDp9s!#zh(BxCk?7#D+vCF#H~bAw=WnG%~{mdZ{X?9$@9U_$bu!ehtx1 zL`;0onZG9lcAN`;QYqwqNt~t@iS;%&HZo}Q6bV9VtBrQ5Q5#luRKFv@u?9Mu0YIBO z$!7qRHNNu8y%{ofShCcrEaL3j)Ju_Y-F?-zbhb9<5<*}sT5yd35P)0CT-n-WreYa_ za5;vNArrcYoJT?-^P@k^g4zPLfXIYsl=*g5Zj^q~QJcRR=*CH)A2MfthG78nri5xa zIy*SY0;>>MHd8HyNfnWw(`QIUunOvPTaTz3jK!co5n4(A>6317a6pt((N;s>q^i4s zM;qfow!dfA<;qGQKfFu#OBHzr?Ix=+Ynn3qxF`q;m7e%B=WpKAs+*5@{9z}v1DDE} zUhLxr$H=1(qjV&8T{vgm3-8IopP3$WzdRWjF6n_N=*heGu<{E%xuY@X8sIp>jsftp{Y;)y1D?ypix|oji8HQ|qx&MwPYX5_ZoN!udBg z7!bE`=~^ka@*UgWUgu68-U3uwo7@TH?CNlIxnS zi1?gmO-$$jF6CXkIG#t(qN+-L#3VofcYC(KYOy2FL@~{%=*+a%5LX6Wi}VcA>tx+G zG_{Gr(RcEY6tgpxK`&6G@od#rY~VA*x|-n&3vql@%B!Vd3hvUPTV6>@7hTwqHrve#9 zH;_4DzL6Q7S{sYOIEH%0S`@SyPY|3_&7_*g46tc)m0hPAg!0z80UYJH)IE`VCvd{C zvWW?bpav1#v(fln5WC^dSwNNwkWlpuRaC23g-o{L6ZHsb1cw1m6S@I-Lr*U>f04fLNB-IDW9XsCR)rd}c{ ze)ZS_NJ@-3z>&`|dwL1)=Q$GqaU3XBX*N2o+8DT#=hBxzBWA1%^xkYdZk1VUcnxdJ z0%0mJ#=)=G=dGgcv&}jm>oH50ya&*}a?G`x6N*MmC)Ct5>q)3&qDn>?4PX(ebb4e_ zJmngxe4}_uMS$!qmBb*1!{;~=jzQ%XBMjvfMKpp=o156{TuxMAs_riz%;kZ_R83EO zyeQ{?fyB?Lp2bCYf0=y!9^hAYGF){VE99UFvucVmSrHNAmo?4v&i(!taB{9PJC&?1uW2J1h zdTxhQjSrwPRF4Qo81>RUbCH|Bc$KO#!HAsdJ?IYZep`FQdfu`rq=}#K#HcbPgVLms z0jI>rg}>*YVf3XFRYNd4?0?i;ue?w)xKylY_b5CW>We#!}KEQ?i6Y`eDCnXslqCUlwho#!e_z2bx4KuJ{kq$}={Yxj=0fcWD(A4FlC@asdlTQ6!sV&j`KegM^e%e~?kl!b zfbaRa-*dC)U*+C@l$0y-GQBNyJLs9Cv@Bp&o;MDb8YQCVkl`g zVu-^$11j+`<4(%PuoPh3k&sJb%V_M0?Li+5NqOIxc}-1iia}_hlCDT}8%d6IOrIk= zbZGAuH#|r@oMqj->$ma8{0raJ%3^HV({S8O>G>F>;@~q1MJ54@+8%NywW=nn%E{=C zQ4_Wi@4vZI?}0AMcOfqgWz#BkBXW!YDF#y$oTC&-|JT0luM5zbNR0(Mp*fhL#DL1W z+D7#kini)Atz^PE7aH-89p0tVdTm2N;6~I;s93&IMQ$A%OFwP)5l=1ucR{9xwt7>G3Qyw<)Nl3d%d7zDi6%<2K0X z2XPzUjmfPddN3%CgVD@lUK)Am(W^fYnx zIf|7)g&h^(K~=CUK(5vx^0^DIk@_h?-(de4w{PbLck;vm1=8uO(u#LwCCG9W#N_Aa z3l_0eHPvp(vfJEMtL~OcE%WqVUH1(QRnLH-7%X}X0lpswNPG8OH*?+<67@NLc&93e ziWs-?km)-D8Pa8oJA_ulcL-*)pBUn4=DXCM4qRiQhJJowg32^O=B+ptR$(lcxOKeYzp07`& zUVr;1+}gW7aF2cSPc*(E+vi)!zKf&E$)I9B0u6RGO{z=Srmm?v%0NuywJ|64ro}<{JulKMLbb<9I z%k4D}uoKu@ssOP-PQThPlc;Pbz9a1GOfccSxNjpO$;k8s*6@iVd(A%k_>_L@t{L;? zW6(V@+x=6pcq!M;B?pVypgqmC#kHFdh?d&U<*J3HvP+Xy7GopHLIkv_%A!#OMhz9^ zX?#oyr(Hesv;g7y6EO38c--{rkiDf6Nq`S6hxZw^@q{~kV5_QV90%ZlfhLQ}cj8Df zI8qo@HD^@x)NxNC1vD8bgyuPD1MKSy0;(3|17>S=-ZeUE0;(>Tn0)V_Y{!^ zfij;P4B4$@ZFD$QAMM=JUntv;x%OR5fI|oTqg!HNJd*Q9ss;u z2fsIUwMK~Xh?_ePyUIDuTwuu64+AKzgr54`bcU;GVI!iC)j(47O zySKig09=ffWF1fR2vX~jO&Hmp;knSGz2vH!C1S*AkNrDdPugCRHB-X?o97iL2#1NOT%l+$ld2;-BQcgrGbm zH|6^*-U%W&?cKBWSy*xwFClI$pv?n0#gY^c_>b1D6Oara@sG9>xGM z&`{G;E}i*F&9iO5@R|}>v=x?Q)Rg&b>(Qa8#)$^%n|DRCtgV-fIEI!Lh;e|rLhl+5 zk3btGPpXUrayIO}OTi5pKC*a#5x^9}I5_4Y_YOcstR*PY>C`yB=%NHf9J^UyRf06W zw~zh|0t3t7j=Hl9P(F87??vTxsQ--XKWoAxNx&Gb2cr;JRV&(#={w3e&2ZmhSEW!2 z8Yz_5aXVic?0b*zODeH|$pL1sK{xV!0IEn*xvR#})w=03776^G={@Skt1a_CI&6KB zW_RuBhoSbtvE=Ej&*4cA5ngi#|yh{S36UX){FiQJovxfAw!aO*vXbO!Y+-g^n`Zb? zmEt8eYvz#+_FH8`>ZapvEK#BH5+b&jVo+5XU@Wm#qAFpaZY4IWXkYu!C!fir?(FeTP+jYuzQEml-+xe5 zknH^%FMLOH4{hvG8m?;9M7D@z9DZrmyk+Y9!EeD6oHc3Up-{&cS#Sp*HMzUb>YIpkwKc{sL-Iw{6 zc6@8Iu!?{2+9+LF%q2f3s50Anuow4~8Hzk7m_!JPyzha}xjoxo*ZGj_R;BpJ9-m+= zW&g_G;o@^WUptqF^XYdcSi$=YeAlX*KH^s0{Ig0rt$XMTZrjFZwN|ZnF1!LIy_79Z zzb`%GGP|f0SoG%-0~+ETfFiM>#QsL8(i+>yZ_?<=Si&x!aG3n=P5zFF_QQqzjyr}e zoOk(ZwG|yXuvN2WLwpkA3@D|EKsjO-$=0+?zhs#o$2EU@4o`TP&>4qnLJpXjssJ^RDE!b<`c%Q?4Dxyjs` zNfu7L;U>!ym8~p>1**{rCdi`T9;)U!0}Ie4t7@R67F>NDgWGErgue& zkB!3TOB8{_TIzEuIoDU z-JNqcLL=v#69Iw&%p#R#Te6kxvQ_qY-kbSTUZ|S#dsVNd-qg&qU1Q6#EL$2`wnT{( zGr<6W$T{Z>bfeMe{Ob3uz0cX_+;eZ=20)4&t8I!P`i67%*?X<^t@W*MncAnlG95%- z0usYUDhG5UlAs+hJuaR8z_^`9N$c$p(FTBIs!Ey}NqLP1s5 z`m&f!h9YeiC}s_U0ccZMl^BhGMlub)FC#G%R5i8s1X6(#;x~oH%QQ>vjy=eAKn;Pm z(bsp|kHkn-PA&Q2$777rB;Mu4Dw*p0KBoT^s#nw5Q6MyGnuXCkYmd z0?=~bUvkX}r89*`@%@&qG){1RO0LK6y)bh#>=AQ{<52Vp0?rbaM*=AA{9~J__D`F& zSb-We#_N|)tJ*C}eFCV!dj4GMqQ*2l+d$?rM<%$ny-QUi&IbuL0xUoW_AoFs020jC zqiO(if@)J>CnU60zt92DrR(l(RZPkDB4v7QNVJGmiJz5# z#l*l=8437ZRKiq7_?p+K=vi&5tVZw#Ks{?0UQ}2=p{159>AX zo#Yb#$;%fB&@q?{2shv#`*;|bf^VAprom;r#F?ZtdcK6QD|C_sg>!K16A=zN< z0u`!w(Tz=vsbK2Y_>QU57pn3@FCtXaN1y*g0Y<8vBne6Wu_yZPniy4b>xn%Ze|2+S z>%M~VN18lV5i?g)(<`!&jkSX}+`I#=mA9{)sFcmE&nt4foA)qGz*9xodMSMy;H_?nL&Eao%Z z$zvWj=i@`7G_#roi>WKkuR&Q*svzG+MT9<Ds&nR;+6hTS4C=``x3ZmY*tlF^hz?& z9xSH)d%?4q1y6f~vcVAF1E}qqI!o7%N}@)Iv~}7n%7o8u!EFFf078H^8D{z&rTmJN zvY+vlsX&AZV?qtHYf5wGAwaMNC_Iwhkg*l%u_SPz50rJl(Tbi{5ZH&&D)!0NuVSBJ zSu^#3P;F!kOmn;bY;?~-^-LMR-a9e@aRN5>pY^H+;GNJsbOUBg1A#07|8ZqVH#w%+ zL{z|O@+PCtUS()C{bl#=-idk|eF8z3VqlT=L&>jm@+^HHpqc)yuph!bR|Jby7@tbH z>`&6jKNwg{`=>(hTfEyUg2kvhT(n#z08WpVz2g-_i{4a4z-xygUH$m}11L=#k*B&& znmWf#ov}bcJOMoOwFXfDmW|-t*dS$q2H->$fA(Rm&9Ft{9y>-K757kEN3WtOnbO0h zlN+k(VQ#2?Z-c-A70~Gk@bC5YC@{2s8OFfGL59yx8&x9N=Vr^jqH3^*p0=%ux>SF? zlJMB5>@P~!oO7zEA%$kp!DD#2n1*2{v$(j667IYe7;Zq=xa%};+*_Wty-odOVy z7`Sk1uiu`fr!O!TP&>tLkkq?=^|ZU!*Q=2mi&s9T_2=0`Uqn4K6R;$9C}lmwy@h7y z>l7#wOp*++`HG?6uTB-+4UhefUbE}%AE}o*lMKjzN5$oj!J;K3sanztiC;bV(JR`^ z;n~}`i1-6bJx1(H)8l7qkoYLped}}IRq*=CPyTOr_UMi@IpI~?4g7j5KF)ca7(}rB zPDK-XAFU_E74w#Ea!MPbiDjj#%V-bMk(`d`Wm#)vWEqS*QE?lyXVHYCg+suSL7I7pwI})qMKI zUQ;t~$)*Qe>2WgHm3jlxB}hDbWSc$RsvH1FY)m$Y;ASl2=2tkV001BWNkl;5Z!jAC4uKgPB;P0_hSO{7oGb%& z?ea-&?nXpge9t1lh%BFG3^p|AfN=N-^f@3HKn%alnyF95VQ}FHyZ}Zyz;do({#5RH z!#q+|bjXxT`5yu~fQ`{@5qO!N7~O>0q5etKO&hg#sI@{D1vC#2(!gv^D#%J(fZ!y? z)6q4}H8eM?aw_mt&)mfppGm@Ldeu+`!1iZeM^8y>TZaNqsU<3CW$^PgZ&GeJ^eL_s80wPwvg1(B!_UN?7CdRCl+B*_-_Wiv(Rf zJDgU4vb3b4>*Ep@j%^IiUr!eqbH*ZSf$U1ej}=b_wMxx ztoPo!qM%#-6o6Y4QWGkhJ!8IsUMr`2x5of|sAlCViLsNNn2Gsxyt-Pjm>TxT zKoe-y*1Fb?Nv^GZs@9l*+D8@TU3@+P5!<8~{73EpJ4CVthJwlar;LDPB`4xAGT-AJ zPOd({{zb5$d)6X{6#wlT=iQYH$F0I_9!m4+5G!Ct?8UPO-KDb!ZM=<_I49XAY9WcD zmUdrwvN>CtS}Csg^l^C6Fsq^DNy+v1V#=25iFSUGc`dxCY60m5aW<+Q8pc4B$aPO`g80eFjG3^Q1^5B&1EKI~Xmj{dTJi%Ay*fgo_ zij0B(W0Dq2e3$jAEnfA6+xq+;sY-WX$1hX?WHiM75B}9%IJ4hx&8%zJ(vFSF=K$;p z;CgReRv#gPKg-uYuYu>s54bCw8UT-E1DjRVyYPD?vtVlx%M9J?cXxWON{Ed_6A30pY>}i$tB%?B zl2VUU87$iDR@#bcRX|X@;QeT2N@cdZG5#vw-}*kNhs7?jrt_C?Q4;;yrIYT$>3vDO zM=SxDB#tD}GuVGuD#wP~Qt=yUQ`FSEp%GIvHU<19YeN_uut+{q+hsp6`xRwQ&Qu zwx+-X#1A>Msm!<+{iM#w`^O4kG2^gnXi_(2QoyAssRR9fLsG?SRF(vzONNqvClxl0 zMrhV(3IZQ0Gzd9pV0^7}x2|6lki<{}G;JPXql92I3Zu4O@1aDG5#sMOYq7RoN|*pN z0=QaND}ca3!w|};DtT_SLW>!rbxDFqKg`(A|HHtFGT~*OF$n6z^bNydP8oq50UriH zGtrp6NZ$zxh>FQD8i?^YRnoY3dLnoqL*_9e$y0#VMg*qk?y6G$m)KP)zBbEBkco>UnqL+8N8{Hd@7;F+C_gE?NDQ0tu*tRG!pd zD}`VigJaZcDj3XA<-fh)4dZ~?yJX+6sjY2Y`Zoy{L=d=d?5B;>sh15PAxGsO@Ty+s z;Q?i{p}Ip$(-@m%!P9X+I=>z)hTmIN(dcRcumxcp&I{)esx5XFyKW4Vv~N0nuH{fm zbR`u6m6(E6K7h#6<-9TR8D@aMyd{rl{v5rA$M(J9w!iw{Ww+OD{fb6rFa{)(WbnRJ z$-TNdH)Z-l_1HsE931R(%`IJS#ro%D(~j(Y-CetQ(kigNzd77>8d4`-yv&yOV>*Je zw(q&co^h^dQ`qqM?<%pj``sVQ{@5ssKzFtDR^qR#smys=KcYO#*F7uc-lKcpas&5z zJ;Nhhb9(LNpJp72ru~`t>&HL$CvN$=XWW?+AE}?t;)c5d5urK~S6aul2@!;<{8~@` zg$~%<=BCeD;;z$Y+IQP6T)x#k@#6Q~u6O=XB0KaO3nnv+-3u zNEjOLo;dYrNgnLRiVZJF(U+e~=MK8CxSh|cR|4x-Mwv+MDkGP<%|!H z4!XWu*Tk^txp7h8k#n6WB9~d@25AjGojOVjLQbmcx z`Z_l{G%OoTucG>GePJZ_HKB@J_&7ghV6hq-Fy3oyk5xW@pGmNo%^XF`5Cl1L*@bG7 zw^_p;vVB3O*B{o59J_x_xu6MpD6_U|Ym~hnWGslVibexHexl_nB$s>4nxTn6R-LrW|L( zZd+uC7)>I<7r;&s#3(pT7DoAANX>mT5bggq`;Jg0pmEw8F%9ijb`odr2Uq+35&~B~ zgg!^^m4pF-B^5;}(n76^o{1Iy(qKf!P2)5geMN;?m4k9PW*|f5A_|NWoERqojK0U( zkzAk`WpejyIV>qvUa=wRq1irAll2_*(YD^~YkHEnj|*oH=-DZl@YT<8tFz--v`_Kx z%YjAxeR$^nYzerj$BJ2%)1=NPdQD%C`uNCtYlMLAcLJ5Calj(`WcI>!3g|DK-k*-C zh_114iHm~iN)FSX1@GpaeW(AFE9RRKXQxVfoSV_xWmp*qg_SCXpEz@}_aV@opp9UFnI zAOIwZMX$FKSxJwg_4FpOoA0kyk}Rr3hJ8+gh!+#=z~;b?@pmKO1@-N-_6T97vxhvd;$A8D|-|=&I z?!+GJPxSkSKO1WRg~CQv2e7MBEp6*k{~(p)v&VP3Gsk!N7KLo0DO6D6tbX;-A-!9I zMyk(SpZi1gjP82pCnh=+&2Y_B4oa$Er8LSweFZ$M-0-|U>(H)O)F;J$C=S`nUwtO{ z#}?F}{9Wf(Zu*?A8$W|W=ZORFDv^v&AEM_1wG${nRQyG3_*4mHDK=Olp1k#yH7it*@h^zi)o(TdHuw z>^gmPr`x^#CrL|<&OnlUz$e>WZ0?^uOgu(R)z;pnN~^KN(4;V3ir(8-#R!3=kSLS; zSixczABsl_cMDZ$wQ01GSg0!xM|(9n*C}N+7j#74p**Ba?96Y zyVlI?hmYr2A8%8jKoc*Kc$QAbotxRDeiTC`_RhzirK=FBVyjKeMweluNGjgGeo1E- z|0`_?fMXpR9idk>0_sI9oZr-%R{Y*rG{cDqw3X2ZzSnyP8jj;^gIXha?tq11c&deCSmpqprRYIUMuRoVErB7=SyjV&f1G@CdgrXurw*RxnkJPI_5od~H93B}| zZz9ywdm31q1Dt+FnVj?Jm}_q9l=uMv`O5jD%GiZUYNF_tJ18Y<_^C9!6T7G)(3sHP z{3shhH8Y$hch6T+fKfSjZe6xHhXegKG~BBmJ`Av!oDq8Gnp*vc0;BSz&Nb~3E4kwd zfJLLod4Y@>3k4EXQM`UZ^gya7(2dC0^SX1V_PVpjb}HCn;5&+&7tb6pA(|o(6e#Bj zyz#rtXP&L%XlH}7M}H%KCg|gAA(Rt(W7w-ov;cN=291Ko^ASaUa6puG{xKVrOH(E^ zDWjzZz+|FeMr%?9ZDdsE(-d2w#MehkhkoX&|Ag$?7grQAJ$^a*Y3d5gRU-lzvMbjA zdKFxr%i}Nnv0Jiwn*y|VfAv@H)R7NlFQG?neEfGc*q)hmpeMoLBTl=)spbziz@9~|LUeroA360@GtJe zH-D&Vv?V)zH6<^gW0|N7d!%T+#siD-n%GFM`8LXCpifoQC99tl9Tt`hzUK0|gQgrB z2hWAo+3Yu`Y0mOAzv{x){3*!>$8n{ac-izjlXq{n8jz9;C>Z zd0Kg(l#8{4XdPq8L{TLH1skm0>{#n0wFW_*!OyENy6={NBX&c~slomvsh{@2*<<6{ zut{hgpz}a7DO8XXrdcvzKL2#91>?V2PfM(~VA&QiTF`L74kXDNUnLCtm>7`csm_<; zno$I@p~)C}fW`WzR@p@8tJW8MKfAIz z%k^=*sywU2hl9D4;du5T?^CLM{Y3BWV+M-_4>3W!X*JL;I_D57+)4HbMwI~t_f}a- z&2;&V#H$EKFfh;@=*KZCmG#yH-~l+m`I21+Tyj7Fi+~5dN)7aGOxZC4dggW!bX+-q zSQIWYx^WO$C7d6?Q7fj$kp_BD zQpMY+5;xGNLu_=?P)$o!OB0ZjJj3kY#MMPAU-Ua+c&WN^{}?Kh-%r6}sTofH#%L*1 zjjD@SjS)CAM#Qq})-OY~mTEEv4!Q&VoWt~ZdaxMwm#v}a+52i!XtLJ2hb`-?wm1|M z;_$mK@b(*;lnAh@uz_(4R)g$zLEz}sNZD7cJ7ZjUzN{6Wh0-jUbCL^2^R;~*J~Qd> ztf{pgr8&#BUoW3KqUxAQ;M@I`%X$80UD!lTS#_^3o8JXM)i-FZP#J7#?@~Vu%EkaC zRj?TMz}SV7Y<-o^s!U}ux$^w)$9sLrp@^=dD6^=3-8%IncTSz@rp;WUjQQ0|C$)c8 zZ~lUm9-)VFHlVWY`|#(gV30_{PEw6xsJi+Um25I)Q4r^+)%GGAQAd2=bxTD`davI>@N04L18mA)>hjTPWJ0SENVsfA&1z|C5)M&kw!?0DIoJMobRC@I*48G#+aMyeH}uEEV&xK@3R z%;`I}|ILJ2U77^Q+R_+QWLBhXWdsq@O}QMbOsK?G`NGq6#Yg&et!U^rk6POzjD|w58wbXBA`no+cE3`Q%aR8N`1Y&)C((7pP zUX?z0yv_Ov{C>QIRnbnV=Kjjs<%e`nA1hd_bc4Z(qfAM_0*xZ8#900g^Pih6k~V9W z5>Pha)dn4N9g}7n7haM6j@#%3@_s!miT3!bbE({vZ^7f4jQep)>nlUqVR6d5_3y~dWG(w9V9K5INoHlEz8yvXfu3bD4 znhP_1Qh`oshB-H4Bbr}X?uiw;=P-vz^xY}47u*Zd`ec%n&8u-*uP_HO{d{|N0jm*c z5kFdLS@BS8~S)`CgZCU@;BTN&_~dS97lE-J{aQSqF?G)jl{t#mYvx zFdHz{sf~AIm5yox6~K!2y($oCh9d;t-rWm`p)NRO`dnAv(Bf`hJuNYtj;?OEcI#J+ za@)|PezsFbcSr!rdZjG@P&JOx6TYX-L~clWzz8rg8iK6=9JRN+4KfNENiHuo;?hZb5=d_ zdH2}!e<)VUp6&m`?cV-B1g`nvx)F5Q_~h>iEJ7tsS`aiYs$PS(x!+4?4#`)MJX*f? z8Lv9|u0~vxB#!*`rckfUuB>7|CT`4)xu%v5fiD0$J&VJE3NL?U{}c92iBMg*gpkCm zt#`BLu5c?hJg>g(BfEbsu`dJpv8Y{$8ma?}JiP|STh-ONrK`6|X%wUR&dY!4j_-fl z*agYskCW3`yJ~yDPU6JCV$NpyXEA5tdf9LiSnD~j)8;90K>R`+bNvbx$Gbj=uS|da zq(bccoyRd5an#BUpL0vrJS8^6<@1M?2->s#pWV5WdxbYj;ynSjG-*)c%Oa*(02;>d zX%%Rs^4JM&wPT7Zkk|tyxkks-0(1N3WhK#x#jL_MCZ-sQ&LnwbdT+^7{mg+yr{3q8 z^HwR|HKqa;yKEAf7`3%yvY1hX5^?F=5rIyebaQiu0Hy>*2KxmN!-iMS!yq%q?wI=M&|q>+%B1;z4%EN^ zdsM~kvQ?xGFqVWU@)0KputRsPs~7)$jT_Vu{YVP=|9EogRAXD$*5Vz_Sz zvSP6n1q%Y=Vdn;OZ&U+i=m{D#?yxjlRL)3H739M;dSam8GI*X6n3|WYs|^`{0#DWz zP=)a_aSI=scmuXBv4!f<6z@kKSPvDK>t zTAwAAP@b>$E`lhkti-kL{Ep6MRugoo1_}RKUnvyrw0pMpD6i|ieN8kG^#~-xfNfn2 z#9NpprCH5HTIjlGF4F7iJ0k!O&$42JctYB$a2l(ic~^6mAN)1tLa@{=rQu;Iy^4Kf z;~r*e-w`0(ynaET10WOtLjdqa-&Rf5&p)Kn+nq>n!MI>E4O;E)Q?STy8tT~-^Hq`H z+@g4SF3Tg{lwQsn%Se1R$9DZ5k) zc)$9Ro9R6nu$hWpnmr_4_ap8Uu%{rf;X)a%0V>|aNE*0S#xpaLwvs@ z=Ng4i>~WHi^i(nuMFuh(yify!w%heO#B(%CWAL6Ts-chCmb{XqF5MBKXSn2HmjjDA z8e3vreQz~({qfKJv70t~iH6v3|K(q~o7c}LJzUtJS@Tx8P20XMu*etJc=eN?iEkgT}IZJijNa*v|-8Jo@anC06v&yFd19h`g$K z@kt9$BiOM?Q|GFe5Sx2&*DpnV?G56n*9U18FaW}4>b$vZIWV84kx)KSC#~g6l zCl>x3YiJZE3(^Ee>DhbOPbRKsrQb$Up0O*e0XF~KiQOs9HhGziM`8q<%@1c9fYaL0 z7Qnw#MQTfu5qFTtyLt7T?6}sd4BMsj?L0u>6&!!BPG-k+P#dz_pBs zP_ImO8D2KrhJ8gmQtT+h>dD+R<2qBhxN5t?+cRTQ?2Q`txE?401SB3tj4+q z^#B592&Tw%b5P0Vh(3wP%E+Jr4aw0P?Nk8R3%3y18gQ`S2GD5&CC)W8x47B!*GPbe zxmi+~GB4x#_y#DTF`H#TV-2DUWc)CXX#;vt)k?#I@EPh+X`iIvl;A$C5Fk?H@7J%LmSA*5;zL|7qAszQ zCvYJvOQx3R%hHK!+sQ##!~;yqE|bg|!HuV0}$K%U4sYN`oZGubg&QFP`w~t3JD@H)S)2@$*Tp zuUzm`MJ1tX`|*G;EEj^s+3VQglI;|=siw{~w@;F)APIxs+gIGR%cr#e*;hrlEEJOS zmt3`*8W-%1vltcLUm9M9jC_q7b=Z?8*F9r_z+!D}gJ^U&uAH)7Kd~{4H9$gzO277p zrE1NwF^MTJ`t`fiG?*b3FJ|UATfuq33gnfWMU5V*;u2|VfCAdc_8K0MkNWc_p0{$S+86( zv%Uzl0Whdch6<$r)(Q_M0vbWUt=y|Cg2hyYIncN8A+r~(bx(Z$Pu=W!tK6mYhu!vH z{YVppf+N)G~Jd3{twizm@fWFhmcDY+u&-xpQ zlKp-rF0mrxa1epijA=h|1KS-l`e59_T%h>DtX8Mijg;|~P_nFqRsteRS1SA9%q(S9 z@;|96d6kP@@ntb=AMgAn^_hq9#Si!yH^}=`001BWNklK6d-bF!nRi8Z` zwPxH8NkgzaQKa~-`QNK@lD3S7shcB^4_A6Pb%hfPx_eG={!BDf{*Js^=!@rSJh)$Y_TqVFj?Y zbplD;A2dV@qzu$_O`f5u=8a3I)W9A36a}EQ#76(J;if}T-<6GY;Ffvo~)QS zz-RcZj;Ruo>1@$`lUW+PXR~tR9-XB6mvS==Xlqsu{e4!!3Ik}ZIzrr-huMjqQ*5gEAu~j>Rd_L-|4yGZd^UBz9I~?AYRm$ z8w_oCZDzjCB#l%AT6oAs)yi25*1GGLj=TQ;J4$Gg zNV|OTm=ss%E#9DY$Bryn{e*zqzW4t%5mAVhJ>{XGf{j{x06`{+E(EUV2`70)0aSyb zYw15XihmF-OX!)t2Zz8=q8CaM3@EurbxPwr{P>>ofYIM)4H%tods+V-ZR^io3EY5#2O%hVC;FTnrd&R{-8y+org!FZ`kIY0rD*z+#qMs6FSY zrQ95La?y&d0v6{^?Qtg$z2_CJEuN@k!?FQbAv6=)36uqPC zLPERnY)=#{Ml=)eW1x>y{b66sU$(^^+4F0E2D)VDH5b!YiF%kw>JM%05O{?BMC*@YpOFzU#8AE`!H#c6?2w*E+GseR zfrg$D=ZO|LySt0_(!=(`1z>e-Ov%If%N|h-dg9P~x*wKEcC*pMYj|f6pyYWFHxaig z=|&vq$Fl?m8|#EU#+IU?5n|866Od~gE82raD^dDc4|}~H)@k^k=W}Z2F5WmMnqxAD z&W|>z_8uPyEZSVIz&)-E7UNn$dU0hl>KQ{)pqS)o5I9hR4Gx3o1qgqjzT{yQ_6f)HUrJlU2-CyYjz7Y^OsMLHb^y z1yb##`U7B8U>N4d6@W#)h6a8>0n+MJ6X{<;=}|vP>=B=s@hYFy8i7y#brS`PVO}TV zHM1A2R>qjBE41DqZW1cSb_}Zzt?tWBl>>_*ATEp_d=|E#vK!T?{ll;d3{^NX=hJ2_ zR^Kg|V=Ach1#0${r;!Row@;QJ1pAtOlQ`rAOl0@0HkIFt_H9u%S_jCg`b{mJs{TL^ z?L)lFGa^Xzpu$XG&UbM=06waM%=#l3v*fe?To2?^wuSwUU{3wq?Oh5yq3B7NqOmy@ zFso+_5(z*xLHRR*!r_n-Z&1##4J3OAa*Q^cs`+I&;xS)5*gXHd(l!WR0gGaOThAh} z7_F<9Jtuj`>^x@A(NF%~tAFc`?|;ks(R>*r5!)CY5vydw6Tj>Be)zBM!pS{))-f=q z1p&Gl!a-Lrov=U-`dE^D@;zW5(@_pdE|RbS{KsGX69bFef0|29h6F?z@-KU#rp8U5 zwbZTL_`GHsAKm+gB~N32RhS5i0a#o)$=)M?+g5g^IB|;L!rU{HdCeY=P$W~XmlPrf_B+4pE_IG>KPf8qtg1&@u;uxSz ze&IJ&StOoA*oJ=QE9Z{7vnN0D6lRqB5g(hbVh2Dn+4o){R@xH8Twz>{zfWF=&?EMT z^KA^3kYvmXQ>F1(xouV)^P9EIp7uDzxvx$8+c%B70yRt5JT<0D6pl1F<_QE!CErj% zUC|zBnvDiPQRyOB%k*w#f|F1c&zcLX7zv*E|Br+6tnsj#LK$;YTj$z4rih}%H%Tqf z_q334rpJxgPI!^$Qf-G;FZ@A=BU1IZXltfEYU?W3C=BI5O(9i6hF!wYAeAepCxa1+uoL!S(iB zvHk@BqcTJWM%6&;DX|0+0+b_`5lbj%ArT-WY^thMAu)~wc%j!aIrL$!lMlAjXOs;@ zG{jzdA?aL1zLV-4l}d>VX=F#5xhDh2AZdEZ=&^#%o5}D-8AE6iyfu7=1)J&f55bl- z5d#(%YAvX=40@3a(PIgk{d$DwBmn8?b!tv!+hs z9jKiWEOYHR9C|hwDou4JuNY>#-+y8a;zg6)yd@hIR@dOGW>F@5j8{yxb6+jsg=J6@zF1TO&)nb1wM zssZ#paz44qpqv_J=EkEtOnLFP0AiTu3Kfkqe)P3lzUUr#>JOA0L(FE+d;e_06Hy;j0AScIlua2wKwll|m|}1EhXplv?xJ-X z-hTenUU&NFho<@(MoWYXc^H+%Ou(LaH}AIaKhVFs1cad(qv&cjHmkgtIb;4abw6I+ znLb7Q>yf>$E1?!DIk|7l9aW10vYdrvZrrdJ?A>7%+zdD=#o?zIWO2Ul8L2Bu1^ji7W=#?0*GQd_P~M_ zTim)WUs9_DYy8Sj{zA#3$3OQc?#}HiZs%M7Acb;!<`3C7sh_h>G46CGj**bVpY-Vsv*&=qW& z_8*DgC zgRLHh9iHfQRq^_o#Vel}6X?lH;8yYG!k1J77QGM+GU-(160le)C`!J}HYZg+i7fa^ zQJm4uo5*~QDQk$ECGx_d=YUd?v!1?TRkMt`$H7K+-7?WAw_49(y{oBfkkKK~A^6}2 z<3ZNN0wbfELPcc`AmR?n2k*qmqgQIF69dWDN-Zp!QPP6@4`X@cAm67xKX#Yc7uu_+kls3G$4N zczI_V-NEbIP?+t#sop?SPNeTMr5v%}_&9)F=cMWS3}toi_IQDaTvKNp#rxKx=ViBkz5XHWb-~w=20wqf)Pr_qgtqT8b&p@l33Fs2~xw6Vo zS+P7+^sIU)ikx~It@jHXf^CB(z??q=Ys_-BIi&<3*gJr%sN>K|>zll|mY>1sXRHBw zsanV;p&-qB8k>~_l$x>cOU8~<*`y)`O*>RUxub!Be)WGP0y{|-J6Fkws&a8ssS@EZ zyNCSe`2-;Q6ML}gk(b<-r@y7=viJR;X%-;?w2xRb30FNUz~bWdZo}5ExqTo0i=VUT ztEg_wluy?^qkd|ri`XpNa-N|QC2%b$_Ux88XbHf1yg;TPK#P-l>Wl4|;+}Zvd+zd? zLvH`hUqoOrhGOQm1&E;>(}GY_EA|ER_^6a0+54JC0g+rxX{!0EL+ME^1dCzzZ*84h zyy7wU)R+Ff^a?(F{ReJ0<2}3>Q@ZCX7`=(w-AZ7w#)-Ys)Y|24UOBDm@Xae{wJub+ z09x3z@Z8d*VpXvAW3k-X%A)Nt+v4_2@tu!6{ReK&!gWeIzxV6EQT3Ml-1^*i)yuql z`%jGd@Nf~6-LI16b(*ESe(P7||4FhS@TU<;K4F7h;<;;%rc|6qrATfCj$RY}s;g7K zbQq7ORwJ=F=Bu3q|3l0IGYq9wfa9H8SKS@Jqdq%~V)6`%gmU{agT>KNB_Niqc}6-M z2S0knXuqC?#u|}mBo-s7s+cj@sjzFJvmTy#y+j_TtEE73ef%>a7Gku2$2(8ue*asr z_)yQc)KJy?mdr%CkI&C+g7U61CMt!BiU3%U^3NO1T+oEkF;N*f<*iAu0i}!#vCvbQ zQh&L-YDA^9p+SKQ!6YWH&H)SAiClC9={4rhHad zQykglvxoKjP{q*if)&giI13+A3u&O#nyhi+1U7m3{vd7w#fP<2HL`1}>$`njR3m{a z1xmH*&lBhT?ri~+4E`#=Q0Mvdb&swNXq zHZ@zbc4Ld4t@;|d*Vt3>M!<4on<#aBMlZ^?_xiGNnXy3ohvWlQ z>SRW!8ybQY0hN89c0KzWcs*9Q4p9pLx#W+vTO#5Whz&~Wx`CSkP zQ$`!`IBddT>N$jl?}IbceGwQ-l0VL7qyhwWRZ=`{5U|94i@L5JXH!7cj73%3OxQ*l z|2t5upr2a5X0Qt+*?MkW$|e(%Q;>Bq3B@W2hAV-U>`_WtHbx%=7%y15S=AM&=qC@p z>)wCu`|jFhn}g{&xhV-Yn)x<&@dmg4v9G#)AN;E-i@XSX&nT4T>z`GSesup^8oQ%? zFG7xoKC-cXY>@wR5*+4@w(M^iyAlO$C3Y{WoVRy$3oKIQJh1a+-+Gbl=VYbyH|&YA zG5G?RNC1q5D;{-M&L4Hh4!*4_x$UvEr?FfJkYT#yxJKIhH8l=()hA#4o?|^3PELjE z_RS0OyV#I0U$+>FRZ2@&VMYtqwWhw_&6u@Z3?Z%`#t^I%o+}`+x94h9`SK6T4(P{% zvpm|$kpOemqI?h*C7&n|EM5DQ6l}Q%m=3S}_&=%TV*2c5Zqv4Jxbr9X2)qei67Gt!q84~D{@M3ya8XKB*PW$^|{0wDT7Mjs*`UwaT zc1)V4gpWkS+9!Kqtr`JM?$;8{w?!eo({s%fc9Vo$s=F}$4OR1sI00z0#F?==Yr$&u zyBTq~kV7TQGpy1CfZ1QY8N%V;iTe!4-`V6gxwR&|S|$@+@D z#npV~!+uT48Mi9(c%b@WU&j4>Ud=pu7URB|Xe~5+IQS ziflqM%Vc%{KP+%dYnNp&YMdxK3b4n^eCF=2zOh9Hn81R~O(un$j%Ye=EK$$nAWPM> zzS%Obj&Tev>XlLO(bucj6MWI&%YmUX1Vs^pNVePnOjK3OWorYmu#_|#oIr6;0zs4% zR2v#4RKs`BtHj?^^%AwhI}rNW=ReMxs|>BGAI_=D$e-2s=_?RCzS4bU50%fr$Wt|l`*rek zF>A*g4JbAKJ(M_&P_bw#0lN(N1%MNb0<_7Tv37`Q1Ugtr=B@BN&|}5Db|@f( zN<@|X79&rtoN@j4dfeEs7g6wMD}O!%*d)MRxa?6Wx1o>-^;Er{p|>#vgCAqqa6d-p zVZ5g-c=JIc{Ur=4CyUKKr5A<3O34df)k-o;1(m!{94y9mG=Dug`c09o40{5gNDxNf z2mvr>{N}Z@Vl;#~pfDb~r!Q0%pNh?aoxc=lg02|WCNMSPq?VZwV_0~^n9zihYE<%Y zE$x*C7~vN>RF>%TVA0f)EvXc~pZk%0RZ?(N{Xl(pZfg*uSpH{+=)F_ zdFq&=o=2D&#}2&hu3b9mD+J;6_`uJv4bK4ZjZf3e$&nEgVl8C>!u!RbP?FAk6STM$>tAqvcdof(``%W7ovqAN$`!{H z)Vvq5f#aN=joZHNHa+omF>=nF_(=PKGiNi|g%ix8SMVA6=bOFbf~W73v|J+Pf;N8qwGV>i0DL%1YQ|IS#x9a=o2S>Dy#BN7tw?3EnhCXCO zsV<&5;H#egoEP||`}ds@SXAuX=~iz1oCJPO9r@5*Ie*w%27J#eNfFkga|*Mm8s3`m!P=@3?CRluQR6NH<-Q?~$uC0Bl z3;>`4gQKSB8<#xT@(E%VRRSud!U9G4NlWSku@Zlf0{6asvaLy7y(G~wXkid488CW) zIJh_#s0Hm^(={^#3pNxMdCj0;;wN1bg%48}W6FB!4 zEXEmZ9~C5W_@OzR?;=QnLywq{=1@vKw!@9kzc_$eZ1GQ=bPzy9!7!)}>Uw=(6#6s; z7OYCBXDiBHv+I~LQvx+q_9T3xd4*O1rt-*|@j6jS0`155uw;9d@=iJRZ2X1{InIK; zgL*Cd^hT+|?nV=Ep8)$3haAJi^dwHWvN&G#B@Ye@D)QBPNqVhoRe9ljlZ3!_ zu_q8S0bB`8M(luPYoB&czVv6ZX}jL}N39e4zEJH^0lNo@K5z=jqfC{*C{Y)((V_b2 z9i^E)Q)mt;Mtc-Bvg-sW%wi;Hx1OIH%EF79tsrj1O`0~>z>ptjqeK@oMw{D`WRWF} z4BT2WY}noDx#|Y)-jQ9_Xrti)1>lQTKB21f&FklsU;tpJ+oKdL#^*lve5utb{{)lu z^F2aTf**bMyBZzBHGS~f_uYv@+f5`x42iH8Bhce}#QE+y3)Z=fPyU`}4W2o^ODzeD zS3aho{Pd9zG~j#;0XL&ol=^NdN+XB_Ku0;6kxFfeaK|t{AqggnM$D&>piaSyC-&WvF;yDuYG#+x(@ExNTqf zGtnVWAKRh$M`M+GuKB9dfYicCz=}@Tb4^KV+9kqxt9*}p*-OgV^&~2Y&JaEkK`yE~ z_Xh506a>6n&~n7>{94CZ4jDaI=XOJlFh8IPV#`CaMv-$VfOX8|mRw5Y1EusKX=HgYr* zE_hWRCp_3IRaum+78ZdD)8yJar>NfzdQt{R3b-}NNCPI*8!P|?DOo1@hzwYaKe$|Z zddw++>6|=6i;9XU8E^t@0Hg#_I;Q$+(x46G%>-THONwbTaM5wX7#}h$l-Oc@MiWtu5h=y5n4|U8cYl3#!pENTQ930#Kwo$;0 zdtnKls8=bhDC@+U;Q&I39s zMXShIrPV~Eora%a#I1?kGGB5w0^9YfV9>vy8A=EeX~v?{UZ6jb9w-6=4e6y)y;LRsa7!N^3ktH~HYM(NqvQ_>k3FZpCZ@yxk zhmGZKzR;0J`!9$|*|RC*_VYnb6*eKcCsA%&H5!Ax#rLtVU^FC(g5Hsn?BjKdRz2os z&tI$L2jUK>D~fXOL0z^YXjGX{QPequf8i^3b{!mS?#;IX_@20Q%?iMlSQZJhR0$&P zgCr7i^w+MOQbG&ci`a!E>HTnLY#EgxXk^_p7b}SC7r5j4Js@3UCN63FJ;(u#lV2EzFqKgx(L+`|Nm_PJCJH$VMNFUB|7 zz4h{ca|d=nL$-jKnVE}LZgo4}{0FUnVk?8@0y+c4WTT@>-WUEPzA{Jci_Rxtd)?z- zQ~Uu?6wTX<8;-STzM z%3go)`VW)<2(LE=o2OS#z#o)Z80+9+E$ix)OkK3{F(nBZ7lJ}{0v2It)G?dZRH|V< z!Pp{^FY2w5e5vYgK4EW)`(95ZP6CyS^9wKdA%MkCO|+7|5Y~&ct6~%^wjg#C+viW= zwX0{*`pV2Fa`6~v=qJhef@ss*pl0g{ODbdj_kq4>me}O>3QbN?z~nblprZs3MKBLd zlz`ba592#{vA1c^w@##{tNNA5SkF;}cM`3KH<#Cjf(WRFKlruIxOZ2T;V%g;V>} z8ICo!F8tsuWlTJMECdu}UhA8n=GH1$7~iAoaAVp# z1Z-4Ls2-Wr`xQ~`04Z`_IC|Sm$({-@#e&fkvcT?$>8Ht`y)y|_pGw5M@YztoML8WE zb+=RzJ?X1^7R1Q!gaA##I0S4XZr+kd+~QS_d)3upRadD#k`d>ArDUjN*@(c`y*{f9 zu{Q|5Nl@_vTY&zYxr^4T=MOQUpn_Ne7Lz1VS`jM(i&Nf%Ta=cZGZ8>2JED``^?kqs6PA)H)tNuwBfT#1>QtI>Su3Fro*) zfe$2+hyTU5kSu1NoY)>UmQc&g!b`1h349JfpI%w!7ard8nt*H?c&5F>;q2jWNy;u- z`MBn8G7FF7WE`y8F--w%x&2mD5#yezrlKUf`KfPeOv%~fAIU$`%7IV+;Pt;#!h(ua zYkQZ#J#h#61o#e~8*9KiW7m0hypO64Z4LOiG+{8R#H|#;b0z5b{GbnjJ>%J8%NSrk zse880HzSeo8JTAqz-XkFoA|+!CsB<_s{|G!`;d$9@@pIt$HbKD9{s9YvgS#x8|Uj6 zKm6adUSUMl+AUvkGv+OKJ6`{RC2~l}iqTM~xQnX4?RQgDjvReqr95xBxwhJxdMUB4 zSofSedGvjEY|k6keniER%3ochS3w0VS~4q%Yi(e)w~ncO%&cZXg*;z13JJ^B&Z%zQ zqhA(qBk7Bf6$zOnz6hd|$=-edigT3CV!tk1`>dPXJ=>i-wO75litGFs41jxU=VUR* zV8kf_SKpBKyk~%Ni0RB%1}2BO*4DvTwzEu=^8(}!1cOzz_~@{2Gg z)MsyPQ=g5>q6drd#g_J;MCa0H6hdGgvW3Yw1Pv^=a=uZ9$m-`FR#_kyaui=_A7mEN~Q1Ik`uw zOaP0{$+KKTW22lVAPfg)15Hgxfu9+3S19X9Mur~2{=V#pkfOdIvqT1Bvxh2oBT>`1 zoV-td1GoU!^wd#RwC7{bM9!X`J7t*-cyNsXT?_@!tDnl52SrHg6HIZPfblTEnV^k5 zqClddDan4T3fo9eDKzC?FRFurtj%DwAE-{vszMA6LNB%I9-l+CSaiYB;j9ZPvtJTJ zu0Xg+&qoQ4ur}U!gz*tp2{FY%Xv4u!1%V(5V+eS(X%vNerKoBQ4%p}VZJhJ*9(=?A zk>`>2WSZc}0?kn5yXc3yaqX=3i%Ir-=UYUh@T(T6Rx{?VbTeizbC=H_78NNTcaqs5 z6969fVedZXw^Wk@4>n>{XLin_4Fci>R?tq_@(&pm!0dmeOVyU zda+41*!rliT7Qhdq945zf*74UuT;v=YTf|rBTL!zBY1owQmdFd$4c;EFJ*gMG$Q88 z#pCYM*@LnJn%(OAOV#5TXkT9Rgy)Nr@aj!3DzM?&Ny;ctVZLK?yKE8nh;8FDsYsE< zC)mbT!UW;o2~GhGNa-VX0Uh0vH}PIf0ZFp2ysa+XvAHT>vZkzrr@+_N3e-LR!XJzA zK{fIH*S~MQ;K|ObwEs-}#lYf9x9Q2Ri+ZeH{(HUd@JFwz0u>S;<5DC`sF9&Z-hx1w zC#*A79qx|LwUI$yoJNUSqkHzt|3UQA^QZPnwVcFr@O|&S`Zr3v zn2I>>GZ86RHTXbOs9AH8uk^K(j5GnXYpUEpdsce|b9hGvbl!r`NzVnzDP{#*d;;Bc z=A0Go){XP7ujhtD)eua%a^biHQ3@GJ{(O~!r2Da8m4QhdQvmeEto98i*4 z_|^|z`&+kr`%krBg1Y(Ur@!qJCO^^hCMLjc5%=MLsrDJD$pOXKwnShpzYcs3baVPr zu?;)k{Gqkbh>?ZHgC8=lmK|Dge9S3R8w)T+OoD1EekBP)+vl_9tycdg_LwBdz7PL3 z(Oa+$nku5Ek@5XJOFNflx5tzeTeb0XN@AQi_>Q}I^_&2E0v2oQ+~jHV6ldd08KD%a z|C!2Zk}MBmJp4PozH#kMAtNJ=6En~6KEPrU-`%edzu%><;(c-lzD44*Rap!-SCkdW z-*`l)NGcd)Y*6Av00vHWYnQfxGLU{wVM!pH``oziApYDW@b{9!(5L_g5-zB#QxHI) z!9mB#(zg)`if3WK!r zz};Rs60VQl461DyLjVGlDwXFGVxrHh=MF-=78Unh07FnIx#rP9Ny@Vp$iD;Fafb8+ zupt{;S|xe|zzE821StZKV`DNN%53>z)EZ99d`UlM1A2{m2gJ9ok%L62h5ikKFu-VV ze(C{0$+fo5Mqv0K45P$<7y~k3SywVy8dHI^z7GzoG89P`l`L?Jsl}?t$2V4snut(F ztBkNfuNS|uYPtmx1esK03Xgv%I6xB&-Zj1 z?v`L5IwgS}y=GU>A5Bz#(}U*Mr5qS5s9Ha8Wih`PWh&!7YK=W?Rm+G2$C(2XyQeQw z^^7@efGy4`f%aIx?LQ3AmsFGd+2yz} zBpYQ#Mg;{L9`<*5kV=@f5d@09gl&4R3rxeXz@{Ubf}JveJ?s{(*s30$UPe_E3^+G> zRqostKCz4!^H|*MJ#XjP&0W0FZF%NfZr1!&?%eU+?%h}a+Fd?(*b9546v^Uq>w`Z} z_p-qA8?tGzAdc*NLw!(2wfCcXqU#O`uOdj0RIPn5Cm$(4*&ut4KWJ|2kkTyuo;(-) zuqEo!d5L+T9iBe3^&WlhJ8s_xKXYe~@Aefo?-l)p@n85RdQy4Dhxhzi3aEkI5*-+S z%*%u75{nWNd9KEFO`YSOc>l+`OXx<{k7QpIlD8?dH0Tl2I>uU|c_N+yhnJGZY% zxl(K3lSL)=BaY>&39!pro63BEYzieg@)kF1X;?{2cvZ}{a zwgU@H$?Ez>t*!MwTcR;N>vn6EC+=2dy7eg}UZBt~S^+C!NGitAvUT>7ied~F!}nMF z9i^|c%4(gPvuM58B_z!NsZ?yOG9TihIyb3%j$$(QTdj&R2GBFf*T6{hNybnr&jZRz zSNyS77JWtbLF%#hzuINqScXf#x#fEGH~C_|DQeMB+HC~1aM zy9^sc->Cuus-OvBv{@a16M#{34yB$tEGMGB8y#`2om1S%;Gi6b=J;uTVXd4f*+DXl zT9XRdPd$pVYhMfo#4m4XcEcls%Fc6r^jDyW2-tzD2xx_RmZ+W%4JvR%yhTr2)mx;a zeFaUFc;ndQFJzc^;S(SM;Gfw{1ADiA|)u|B^Fki=2EX zl%&}U*SO2)4r#Vnpo)cSsV2ejSpbW=j}QozGpvfQYNa}i(_=qfJa1ZUrhxull33^nak8$lvpfD<9tj3M#yhAZ-R5gs`AL}$YbXOE}DnV3RvGJ(o zlE?vkUpTYh#^)5!_hQAs%G)WVj6#Lhs;!<{<(zJM{Wl#o~G+tdgs^DsVD=^ zfPxIrudlBcm?2T9B$!w$+1MfeFTQj7?4|CJr@ra-eelmxZVh(M1Rv}fQ?*;Z_Gve5 z&N6rM&~{b)B-CckB3kby?73n)gCW8>Kvo zjsnc1_kaC2Ztn*_Gau%wcO?9uc=3DEcwpwCX;Lu0!h{wB%b@5?hFC7M?Lq?AXcBq} zHfzIUUv*vGbKI`Cek28QOSqcI9d-kts8}IlF+_F5@<+bXvnY92jVi1gp7=dgjET`m zNWiF&LcFJQ#+AhhxUPyXB~Dwq?rE`6P9NRj&Yj$yuuoDp6dE4wQvRoyr28{l)R?|EJ{r>DZ5v=N_fl-jS3bhZ4c3K z43%+sP(lc(&RNh>N7XJD|g*?J;mT-xPO%)+01bCqCC)!}V0KwU09Jm%OvrJKVP-=SA0ABBE>T2asX~6HEvB63esIeK1lZJh9jT6;_IDomd-$2^fgZv!IHI*a)-R z0@Wi1wekIC9#!3HtDoj#ku$Tt0%tM>KV6}o& zB*y`Yp-(ohjFePsb9b4gQ>D&tV!l7Ovehs&3T!|%4}j|;5kVpdkuA|)w z@Y(nDRguYOgaY7_GX|JeU!npvOce^UUJN1!5V&fyn<_0 zhbabJsY!TRdQc;>Ef8=w5T+w=ZEy9+1x`aPA3m;tD$ek@(R&0Rcq*qu1=ju$TqiRV(^SQ*%4 z?}bazcPw1vp8C@N;-*epAiz!^>zNa~Lu$sP=1GEt?)zQKP_ zBwmM~B9Wnadma3PNX`tc5qp^Up|9_z5*7V-Zn`_YHxyF=mgwuF&z=9K3dC8%kC*I$ z$X}+9s?r9{!*@GVRc+~UsDlZZ^YH^LowbjCNrFoNB$6^O|LFhJy#F*oBdti*r=HGtzZ0CQDPq+Sj@vPd%jSnu@l6(R90ar zg-F4wnnukIqw1hTlQ<{FDi>{7oNIa!*<{-Id#bqnky+Vl++x|+OyIFR(D(dXcyl6f zlY~ifP({+%`6$ce)S)7>@ywVSbuR=Aapt;gRVLbkM#D(ez2KFbxXqA^Hsb<}0*Op~ zql}1}o`**i3;|Zi(lIDKP*5}5HSTMW9k7ZK*>c3>muYwMis z?)CMk;)2)(*G0fU#+rZ(3XyU`L7>5_iv?S!9;kW*ZLGo==%(B+_eZY;KinhPWUDk9 z1#(0^fKF>-6+#OfNhoN3QC+?DA=EQiyH-PvSq}m=sqOXMvNow4SdPK?eHC;IuH${4uPC9%|821wWGB| z!3Xn+r0RJ4ngS8lPSoFYvB$M9tUu#5maN|9`fgu!XO8d8s-`Bcv()5P+C$@h@o(@2 z30N$+2J1bAo;KahTf9LD0z`g#$q*M&Dl^&T;+rbUY?fWSYA7W4vv$?ePB>5XjiRIh z6tPK+y18de($GVj3^hJRs$COe#3{+ z8UcXUtl!RVB~zjMBV~uRtpVg_Aev)ZTLm}3?~E@W8jqhIa&n(c|)U{zhskJ^XQk|v>6K(E585w z-?^P{{k_c&)yMz^3R>^^%N|kE4>~#(>xKqKnf2?n(h~?ars(_fx1Usejgh3eickEm zMvF05_R6^%YPj94+WfNGeq_i5beZp6c4~eoDN6}&HbAPC09uJh5^{s#Tf30P! zRuQMC)TcDmiMy3ju*i4KoVQwnV2CiW*OeI4kI{R1Cd78c9*oO@E+3Ts;}aEMkJ))k z5-JIv{BoizGx59p?K?iX6(|9V>2uDRjsofjhmgz>P6^db4D!9ZeHOU;AYWPFmNtO{ zW&X(xl8d!3hRcqZKsTf(oNm$pEcnXe_YIZPu8>9zZeT zF9I1Bgg{5I`G0(#fkqke!FxK)0+L=OO&MzX?U29q>%-sS99a)ZjYI8(o=botuz1s7 zTkyqc20eZ3@zC4XlGXv|@Z%HN&RY7L=knO#B<*X_X>dTbT>=LzL2)e8f2#pRh zCP&V_a;*dy07j{+woOu1HHbbCEOvBGbxp0E3cfJ7LBz%?zBoOk?uYg4_=ifYIovG0 zl8Pj2E4gvmto*%O&>Db3=v#^br1|e0VDfZED^R5BmsT(Ax{b=kye{!E2 z8tk)-ciEqGew%^^6vR5Fh-OQV4Hag3GYCSgQW5oVRRSHp(rL~3Q{BA9o0OC}du)di zF=mis+3GYT${KKgkDr_^c_`mh0v7fBMs3btZN0|m(4WQLymH})0?A}>a#+`D!B>SW zc^Z&L`zk*?_o3WzO!F)Fzyt>|*R(}FR#T_Vmt6!{UA=T%0Dw7*>Qi*18lORLPS=## z?$(V9s`zleY%GG=It$VQ5QsMY4mWe|a#3JO?g$`{jmhrG291p= z6V7!KAQA-9R)DyOgl&cg)xLl&Mkoq(SpM$Fp4Z&XYv;YdPu3l}{gT`A z^tX(DdikVA>>SwnvPO*n7y#akd0>RY{+%yd0wEHWOMF#qYa;t&+um3y;Yw}f!kFR= z?vZtX21uVZ3>3~Q{f>YtwXi7e8IhF{>&HWO(1%W^;o%3$TtzY*T%u-9+Mn z2VM0hQyo~$9h5**#AGYj9~uy-Ah;!X zKr&iEx!+)9IXUp*fR-${&lGWx$VLIc$Vw6%H8etTK~mjj+YtzaCU<%Q#>R#vs3U3b zx&~FK5O4_na+&XnvOIsVyakb^7YE2h%%5RRz)??cE_O0 z_9ycg846BGU-v#@^bwq<4xJC8ih9keIc70fG~iU{g-~KtK-{G%l%<3&loO$4w2a6$N zNiu=}695vbs^yG>0c``58sRc&nktI)r6BY{cA8**5XILDj;81=a4%fPq7{$nI*`?t z=!YL-9#?US!`D2C`Lko<3c;dB`1I(_S-f6J7-)k8y`i%0524?M#*L_E6~+Sqr8L!4 zc;un2Y9Y9_zN)at0RU8upr7*hx2~OW*DsxR{r7s4dF_^Db8f-%EpE%R-&SG^AqT1> z*dX=8Ns7L72(VF*0v*+GWT+@6Az&nY)rN4>)Y%f%>FvE95w=Rh_>ceu6yPtYY|(>u z>FgnW$I>-VE4fAAJD@Ec$Zg+jgXC?NBtkt@Oq*KUJvcU?h!6wG6j}iqq*6)Js!dD@ zdmiOC|cXn|V2Te#v; z_vo|Vb<<}paVHONciUh68+ZNkX|L`WfV=;9mBDEEKC`X{PFQcAv4A;(Voj|AAXIQk zz_zwc*6#pCP#dAg_ujhZ`tRIug99XE@gY7LmZ#no?A7?Bg?%KEH$T(1uD(vTk}3sM zdZ@!|wtUHb_}bqIs6jd8V@W_PSiaRQSoVlJacH|cbL=A}In1_)kv9osC=Ahy&$Iae zt`k23NP8Ok>5N5E8)XllJp7&nMl@Dxbj*XrZ%I_=;I5ZFBgED=SO3k07_pzrs=K00 z%vDUEvkrYe{Qv+U07*naR9yX#_}=3O-gRztSiSqK7s)UVA8UkKFRu|Zr@le4542^g zI^K{^ptS>#6PN|o|7i-yd4F5PwtDDb(Z_w9vy~fPa7$KgQ-3Z!s66kT@BB!6OsyqR zvW`7TTLB3jsHns)uyptw?ic$NROZWq#jrO+oaeuRQB@lr|C;RQNALcV=4i5>78BG+ zA)Xc<)-eF2lC_KfBDc2V#cOfGfb+Lz%NJeO>f8W7%GctKjZi%kB8<# zOFt;t10Ume{2Tk|Qh}SIsz(V}jIvig_?Xl^S6NxAdH{;xbTMLpJ?JP3{fn~mKC8%V zEGUl}xxwK0`UW|Cf}?wPZwq*--_Fy7toM#;SgSJY0Lnfx-OM{o`d;!+G=$f-m4mUg zA*8LM#E_NcmH}B952HX>cA2pnP_S(NV6A8*Mvoj-_Um3>uc(xKItG%@K`;f$?Cdg{ zi+xyN5wH%GgDQjQSM5{u9LOM(ZKfxHV63H;d4j#lSWcd{z|S&c__NKMq_?oi_W;@4 z$U4zxcosZg3^~1*MztLhoeWVQYlOBD!QnXpzE~3gWl&X3o<>lGt*K2V$&+7tu&D7I z^cO*K0({y$!Ib7>`;dKrQ{m6huB_j{`VQ3)fG@0d+!pp)a33DC(B_niC`wvH>Zj`@z9tOu`GFR^S3FRf?-w{4$l$knjR1 zPM*$;&iUHUBqHd6PYBRF{<%MPv*xW)kL?Gq|E<pc~D0mHa6i^0OhYi%pxQDhb`DO_K4GqXY@DG&tJAF6Q zMgdquMN%R;p^YP_=v`V_^?@VeaSZgvKG!#D90VYTkr1o5e8GMA`rrE=Qu@yuR4rb* z<|zr)9oh41Kb9ldyu83zx`WFld~CVGZj|1N<_|*wDs3)DYyGIi7X}Q_+&H@qs3sT1Y6{9IA&)h`^vmSdc8iLodC0^8u$3y z*L*rw;J(0O2-x*+XcY}j>XCzXM|M_~j}T~}h~;OvD4SFUEV4NXCJgx5aA?s=2N08i z!h$j>1JXy-A7{#*%<3CZ1`6Xs77nR+<6&pj^MZlTIFAa&o2)qqBoKS17i=fPsNCOfVya&LSm_dw4g z^AS1lT!U0uweIlqq3+h$xC*La9aH6S!kCMYxfAf>GwT4LlLgf7-np&&27r>8LRbh& zEvi|=Lqj%i(hncUgy8&n9a7lPz)HZPZ62fQT&sv?jjB(qKLv#-^I9NWr4@K^cv` zU1J8YD;H1i7bvj#lt#g_n9%>*2i*zK9LI5$3pBI)B!t7+L{mO6spkGls?0@i@>yB} zAb<@O5SRi0tDB5XxqK=aijFLQu(vQF=*6NJ1{=m6qJNBP8%ZO?M@aP03pO}-&sW@o zm`nt+JuN?}zz61p54};s)g$o0GW4nk>Znz?+Kg&?YL7d8Y^PLD!*gqD zY;}uQZ*#NeuT-^|Di74VKnKH)bkAI@{z8C`2`MlawqI1P%k-@x{xLEl@sOGGR>_VB zdO3ETYXsO*Wuq6J*U|S$Wty=SR5WbAr9VNfv7~yRY=bh@>tNe8(q>e?5uiu~m7xCJ zU;d>#b@T(T(42yf2L+48`_Bh-p?}Wz=Tqe)5Vvs;449uLHUkMx-oe^Z(V_JKdM-0@ zxfk`P`q`avWhk|*Q4%8VUaDc#l?kf>_*ZZKg67;^yLeo_d-Alos(P@W5AS=!-M)4% z(+gWzvGq4R9#{-1ANu+?KJhzl^E2NT5Fz1075nJkH{AKt`;#gQ&mHB?Ezf>OwCKaT zUrmzFu^$h~lgPOHJ#GIA)Y|ZS?vsA8RU2Ot_`7?z$18952q3eDRNF}kF;;=fA^mkE zGDrkb8ER=q7^h2ZASkR-5u?YLgb1%kO|{op|FMlhjL6Pu(KD((^03$=6(q{~ zITHe0vEg~Qc=Z#md)h)**VwGNihJMtnXeSbCfnL75aOCXce&0oAenX`+G4~uqi?Ri z&y>ksjXuN1r8O!BAuhvj5`!d_GVc#qtBqcDlu<30&tq4H#KsU{6n1<}$3l_kwnk-#**2nxdS--N^G=TFud_}2OOEm*876!@&YC;S)&*%#u?i2Hd2~(w^st9sLG~Q&=KorNYn|* z#G815XiChftffjjECb7X$uet3nU|}Ex{Aa+2>>#f1c+ql=~V>8%Q*WCe+br<4fK-N z))O$K{zxjnnE*b@dS(E#w{Ob&)z&JogC?RXiuzNbnAPdK33%0o#XLwH1_2^Z5WYGT zSWkcDns~N=R<0+evZm%QTQSN8h(XW*X?M$N;_MM(AjqPR)@Y{}eE*M^_^+bklo(f4 zQBmkyC&gIAHt01aIJ2Z}NywUPk@1|>czfy7^n1&~hO;uJb2)FxCItfoO;i-axeb&s zO9EI{-_Cs~`lQvyiQHqz1g90~?5LHJ^{(PMX9KF-)nq6$b^t;TH5F?>8GD{Y1fw5p zJb~?p&~HqD7J8nnzq3vie)^XuPo3?$XDtzUgrRZe!m(t8hO+#DVc|2;s%VCLvbG{W z=EctdlL$hGz#Em2Ti4FTP%#lZ;ra;rnp)cQc~{OK6A(-iAbf{U;7pyq$gSA;yubkXQ;fI}^Ock1Q7`2g{K^p#;Iu&K}wJ2X4*gFSwD> zA-D6*AG-ZJe<_d0+?boc{fy-8)Kju>Uy2&`_7G zdQ!<0`saBoXW{hmof`cTgxmm7U6W=yT3v|0cpv8*yFta2_mfB=HbFmOpub1Sl=w+x zSFbuRl1XSJ&NF>B_{JHtSGaXszbsG$-IBBSi+}jv%m>W)H;)#4)H|*Wh5W1 zy~)!keInbgGzMP<*IzMNYl2`@MM;Qk+V%%JN4wwoiCekp1;! zWKg5Le?kWibl%XLM3BIcYABRQ(39fKbFuB&mE znFZ(P@a3IWInx+Gxrrdz=m6#?PMvA$ZtS&(wXNJzNkG&o?0U!jRPv8o*@W$2i&V?W)vH_a^wR)SIy>P97$jL+R zYStZnz|11lwaZqHDZzyux^QZr=Hg)sV0r-V0D%A=0_ZU7jvdc;)+UUp3duj; zPm5oizjU)(z4`O*{n!3h6kwh^6_(=%-&WNb-($Wzp650Ju$%vvQZT;@qOWo$DzUdC{`L)2Be&P4GZYkaa3GFm{jY`Ij zSqls2dE*ldrr)51`iHOoKnX#7BXJ9$oh0@8$9~84^;~sF_PwcAl4a|jR!hQxT`z0g z1Mih+(CDyclu}uQzD-<0Wtj0CjLPZgnvp1$GvE2lv0YN-P7-W>jne&7ofpYaP?O+0 z704nvvTD;yZsD@cV%@N=AH4o|?xT19DQO?d??=uCqoDwRoOu!ekw9+0yMSVZu81>O zN2#-WCW+Ci>ysW-Q+>ZGyAa||?vv#GrYFDd+B>Id{0Y5^A%U&rdSg@4>lu`M^FS-E zp8G6ilyI^ARet3t6gb&diX2qV7cATC4()zbU~SX3uPc7t{;R+C$#AOn1{Teb-e1pR z30S00cGgn2bnP>WosaE%LrK@d3SdMrEtj6j-~fLPGVy*jChe1Y&2PctLtE)Wu&Cx= zFUEpGBnLuDjF~PJzn`IJGW484*=GU?=m}a7GEf$$XpUD7krm zrA5yF|7Y*LgY3$#bHCjYXf)73H!{!w8ad}Ym>fC7FqBA<5=8}5@2On&d*yonxLoD3 z|8m(?&z3Fe`AK#uJW-SwWQJkp%9Mwb!@Sx4uQD1t$mN4Xp$tiNk=(nrZ+=O^o8SC7DGXYd)%L4oX0)((e;xZ`O68qy+kA*whjx>ZHEGs8Sd-96%^ZMD}=BwFDuvS3g({ziX=N+|8R; zErTnn=M7~xpr>-sF)z?YaCUKOO{Fq@*0NwRIowlfOPCX*oYC9NvZQGpnnmmqgBI6k zc%aET95#HU8!~jHmuReU z^c4wB)>8!9{P+g27@XE*|Mer9STeRzmfO~G8L*gtncgyuWu7NwOSud76xt&UR`yrzJZd0TJ<;lXxBULJtUOX)hWRmlnn`B zLKEkmc`Dimv3>|odkBSp+PwSJo`Ikn zeH1sm^mR`+^b4lXjC9{zlin$qeQeZ>9ZaoAoFTPpw&;=EQv7eDIOKKVz=EOVBj1}U}G(+72q8Pmp>I5_9VO`hwPuKm3GaMRDN^%VctMR`ru z4(M4k%mAwiHW$N6VeqF=5q`7YG6Mv+$^_3s~rOtBpZfLP#6jKw6!53jq6P#%r2J>a2`c<+wwr~7tA}AG) zQsrPVT50k6*BY`h;J(}s)lqsX!UTW`@#6RX4`p)IgF2$;T80*%tJ<|rTPi<-EM(Z1 zlpDYh3aa;fH;8kE9?j@WRM*tIEA6Kh7>~gs=f{FopH`-N$L60Wx*78Mm~XFtp?L~w zx0y9pNhB@ZC{`zjs#%w6WB`jqoS|x(SV$;(_Y1VZq2{2LB>S)y z(K|5+NLb_CV2E(Yi7;7h;UMe3c>S_u(aCb9HB43ummK;zhdn-EGm$p+L8?=v9*_)3 z>QqZCto%JJZ%SbyTA1|JkfFGLCmCLnr5J%=@==Ctw- zVGK0N?O7jrudQzoeTl=KHG)_O4lUGc)}b+;ym_q@Eb8-QU>e+v1?zN}9ofId7vTHG z=^2ocxUHF|{nZDHmASM@h^MDVPRG>QtK7l8o80N6dvwT}50(ak^83s(fKkmv#)<3O zD2J!S83Qy~%}-}4eQ%4Wmq>C2AfViVyt2&fGlCH)eFDe=UE6FHJxuFF z;Uj8H6dgxBtdP)J#uR&lD3aN0i8J|qEoZf{Nj91w5y2v&{AA})={t2~w`*uL(1krF zBZ*zHT4q=a7evF3GcVYFo}J7vw({`4_vCO}kT2RNIUB%tW-WY3`;2STaslVwS`&49 z+B@}Gm)-sy>lGxl^Quu<6>Jo=aNdo5irpGSNkez1J9glG1ut=6v4^}bHk&ggFcG*` z3>E_=G0+H;>|!~v=z%4FkPW);sjs<;yx1o)`i zn>J^S+xOvHZsOF1y7sOuFRDF+M60yL%fDHrU@??nPy_hz=l-2C;RFq#B<}z4EoBTt zrY^8XjK&CfSuFbEwhhmzod!>18V2c%XfNgFFaV%XuZW)@D)Rkb)Yygf`TY0(cLfIJ z+f>)O#^Iyg+Q~*j+rDMaN9dS zbn9RIFDc_DH(tSxk!|LOHGr=|5D117cE5(&ZS)8_Zi%VDdNECi8iy(~V`Ypof)rK* zN!yLZ_dTls$M%gs5e441Cw*w^0xZ-M@!D4g#TrOeil;gU!vNJ)lI2ElJ=`#WlFG^+JH??^JbHwU^jgAf&Kt9GnT zfHxHT6Dh@b0TdYs05tDN6x3AvETfrM87x^>ab(&&2GxlWB@9^u%aHV4Yn6)$nFA8t z5Ch5_&>n;9(KnI9#QH#{O|<#Dz)nw>3@je`jmzz-`QdQGSkss6+O>A%VKpYuM68(H zvK)c(SyCsOAAo)U#Q3WT1v)n_@jS-khWHWn57al|Kyt8Hrq0*?$w>-x-pfkyQCsSu zXxl*VFP;Tw2ucsiw`J>^`Z6j>Evb`Z0{s`c_={&xcu;Q?!uXhu^5vPU|Ehzjwu!Z1VA$!5Ikab^N&z@0uyKgh03NMf zL#=CSnc!)#)W2I020MV`uA1u34%N2*omF7ghw|ku?Gvg;%?F z^|DGy$fC&xU!yIRP;{2_UHkRI+D1eTcI7flq_cuJ}P95D<5^bym zEcUr_q=7(dm{o4h(#IsmMWB|o|NM9VqiTX-h*<_SyLlLY_HXO-#cHc^rJZt@7R?pF zk?b{dNUJik&)6OA75opbOJD22kTUbu<65UKb_-TLqf8}WQ2{MaG3Gm3W8Jhwv+stV zN?y z`GfU>vC*dba%|lGoo|^fP8P2J+;19CtZ;treXQ~kNWmgvB3?!~6s#gl08NL8F!UW9 z2o7xkBeLWe{-jQ&hCWIb5h7a!eF|!5LLV#x6hdUqHm=b;IE08GH8!?L;nI3ET2zT= z!B7Oy8a8@TZxZO9C~UuSEwS2b{e#J$RroH44O%MT3TDG+R&8@)6OZ z;rF(uq^3>O3EeV8sUjz0KxuP(ej=tkC-U$-^Vt&zT>JS`o-q>Wy7r_}xN|+CZW*oj zq#~Xi*uls`?C8cifNR`{<_WH4T$>w0eIi0Orw{26WNjyPD+8G)Pp?Il zapuAY6}=|&U_C2ig~V+1vacXPZ5@549Ukpo)= zWW!HP`;S*4-=i`2%!LmLpoaa5EyH;f<@M$@Jrli0p`+pek%`5r2DAcDcvjvETgEeE zuZ|qpqVESqZhjXSBLTd{3pu;w@`sB^SlnCIO1 zwuNrmtd%-X+2gz4e_3-Uff;Ypivdb$Ca2uz6w0ouQLBLapZXK^zZISP$5n>Kf?M0n1fIbsUn)CxiuL=?^g{zQ1pgUry<0bt30kC`~b&0qGU zyL9o4+x6ay0zY$?J?5s)S|zpFcVGQy1$#wq7>n0@&W)Qq&$SS!t*zJE-}LIYlynHn#Ad0Z>}++l8$Euyz#aDP(#6xV zf9zF26>G;tvPeW+@QDGxkK(8DLV~i8)wOQ<17FZ}x4rulDXgjwr58d|X_IFWaQ(bp zPxpQr80goQ3=~zZr5cq}ELic3Y}NGRgPdCQ(~JKp<+JG7fX5_h#d8OG=K z!J_#vi2RHiJ5_rRdu$oWSZ2t^p+e9>w6d6H-DfaY(T^MdfFyjiK1W;MK3yR%;<(*dk8x;nDayZ0ESLc z;9CNp2wh@C$X15zTfD*Yu4iv!on&l6BsKRZz!<6*h$drMSEy175Qm*t zE+gpc(lV44zcH=-19b<9iOAOS6j2((ixoJdJS(bx0*j3!MCl@OhqH3}}S)Xiv9^(^S`q@&sAJpo?OFQTGbu|`km?%sf|E@ zA!G;o0t5w%klvM+*sM~)JHY(VUNUIcGd&c0C%OEJS(08JC-2Z1T{Kz5TK@!HaO`o6 z>gxu(L;E(XW-iGX+agWx63<&s4b@MMeK!A{+gn~%X(ljo>Y&Ke#|(!On;lv{C}0-cjR@Ez zenIkYNSvE64x%MNDVQ2Fb36@HVuwvZkxZu51!4>Mo~U2fuc+oG2urYMpj2}k91?LhVhm3(3ilay6oCTWLl(XIQ-Yb8gv# zU(ox$zy62r!%aU^2FunV_v`k7!MwM2_uaE1xL8PZ&)c}%{Du9j43}?tMK*{z;0z+m z6oiF1bNC&>SS0*+Z+lI1$$C`4FS%C{3@ja^;&(7#n0n`RPkl}5tIPrQi90txFCiUT zEXA!-vS6`RAam;M)o$zC-&e*9e}Ib;crd1l4`6zWWWso`k%lCo1iLdNXeVGCpunE{_l&7dQ2CSg#SLEa$KTL1Zi&pMYQ=6R8 zY6nwWCy^I|Yn=B0H<>>Ia80A7xQR{4w}%;UX3_6w_9lq~0z9Z~62KZhVywGx{)GF* zxBgdm`ovy;2AeQe;w>dUV6~{o^dF>62{d6oLof;zb^5=OVTDQ=*kpxlo~R8PAaU{9 zvw`^KM%elCWa==V@|4J_h&5uDBc1h5!(Xl5mrqoC)2tKJiKTtkzx+SoR-yY%fO zJ34dGBX0VfHEzq>-*qPr?MUY8PJ=}f1+3%7rqS-?kq?u5^#vBoRbu{9ypH|`VSgzP z`I~=J4;K9aSyd&2hr^9?3~=M*NAV;ZJTu1zXeqOns zOk~oW6VaFGo#?6rOmILfI!6s*t$O)Mh{e+`Qdcu^_xd$keSt-s7v2enqM@-_^#hkL zo%QeUn}G)*6#-`=j#8$301IyZ#m^e&u`ph{E;~$z8C#PpJ zA2CprG0cJIVkvTS(v2o$(ReeY>HkmGoUg&M$UV=4Vxsi}OYR-hbjxKq`EGTU4q>Pp z&;f~3Ub;Zbfabi1L$$GA~rCc86a zKrWs2nGQd9bzp!NvBB7-nu)I>$lX~BY1XO#O?j49YF0QJbxlil!T0c?8W2mCg@B#)S?zG$owuYs%y)1e$rcSA zK1vidYo$~xIv+rVmx01eZ%TlxJ-*qmpl}`j?gt^xCzhOX*>&jaKto2Uw$9C4`h;8l z!0(8Of#M;V6~wQk8m(6k@1NSR^qO}cEEbuGvXsN3KuNkn(zOuSyW5_8fwA^cW-pNx4vZJbkTVb z14U5}t80`Q#vYONBwNin2#8b9zZ+LovyOjauWO|#2tyG>VXd;Cr_5Ncy$y8~=7{={ zBG!jW@SsMm$;s1~xcMudaqVZ1DmV+c=1%}AffxYbsiQlkj*U-+U&NZ%{hG&{c%7@# zc}*abpgI6`%*5I5qn&TN(GzAW=!uvRV7WMpX75mxY_e5b0LcSb?CFxY7GsU54dox$ zg7?=y=hnaQUtDJwy^(8eocvgYGuZ;|HE!~(!~mx zWCyX`%1>7DdI+OYZngC1X)FBfJ+N5eKz*_w6Ie{hT|GUDRufUaeie0313#gj2H>G4 zsC9!Z3z8_0hO>~!wDr>?a?2b87ELA9|3pB6O(A7Il1qcJ5mnS`hrHsJ&xrCF^`k=4+SkRIfi1}N7lB26I0ZGf zSxf8HlHoHBll?V+fcu#Q*pdOp0Y+(!$otsVIqF+^{J<7>6aycCL{ONEPqYxxR)A|N+PpbCKe>(hxtPNbL!kRQm#Y&)L09)#uN5H$UFqF5m8SKSVaSp z+as1OD*%4}S@;96ruyC+2(efr>u~>!D^;+ME1n9U1?5?=vjimoNPrymQ9KA_`iC~e6HMQLR0tXeG**om`s9h^%X=pd_a%PC7|5BG}akI{>}eU{FxUrF9kL_vG%oYiji zV_$VGqb9jSd){>$U;CE(_|!*9Cev#43r~eGFufE`RJ^+G$Op>;#y+ne*LcPAY@#Cs ze#xp3jO*yUB@kxHlru(s}}W8dqHC4nx z6HrNCJJvA)M_OI*efBaL@HLPBq0W}=n|`Lf0DTvr3%wgVgipkJ$0tJciZ&S^pV+S! z8Td|6H@P0_=7{9APF^Cpkx_? z!hjFy7)1bqY13dzqC1h{g+9s6jTqMWguIT1PD1*Z&}8HW?j7KYWt zA1u3=P(^)h2|e66w21hb0S~mkbV26nrQzAbye3iQ^cP;$%(8^$3m8a_DJWs>h1w%g zOAsOO*~N-Bg)h3tuu?nHJZ6#`LK~2q*WLLuhji#*V8cc$H}1V{z9cZ=omHItDKl0m z8jMiKwW}8_!xO2Y4P-O_s(z<;u-K!+bHR#Ft6t>*3WdG~u2j$_yrB;x!6D7lQw0r0lai9Jmw3;)zUlCm1&c*iC1;pDeH$7XAdxH~Hn;uUNfV3FS_|!l zLhA+t*Aj9WJvkAZ$?U5T4UQ@2oNO4kyhvAQ>&lk)?r z8VcArQ)CsPF+%49K+jxozbIEw#fj!a>kDm|lGT&YPqV>@-0HHw7C0*T;KjH}b0uig zI&G0d(C4k^|5i3O8Rv4@nPf#}!fe0vZCoBK8jQBXE{cZ6S?efo5o~roivS5rxEg_>$?kz?{?v^gKSO|vOg%j=PaLKtk(G|vJ4DoIf>u4& zzYnl7WB&baV%tJ@V8>hT#E~8D#mG@`xDXlS3U9-eGVEbXLQJfCP!^VZ?7n`80Ou# zpWq$oWjL&9j2qiJOV7Xg&3|$4y!dsM!dMWu)CS6S)DPAonzQ6l^@jXl<4*<35!dVL zxFG;+f!`j@n+Z|zp4WUY#?;=1ahkvUNd?BYuK$7N$jVdjUo4nt0M&wQ_+1K0_6ID6 z^_%}QziWGX+=!8_$|`bw#zghsJxIVi`>!9b8wd%l; z;=n-CKBaJYF_(A@Jh)~S*}_CXscVAD1|S(Vh8}DNX!${jjVNRgTaXb|6MM@@=wO$0 zy-Cc6s9pf9NhZ3RhTjbyEM72Q(}TLi{qas}d|;SgA7z^}^O>(0@P3J>u$Z%9h5T_w zGF)Fh856K*GgbKG#|)>P2p|p3TgJBOU7%f4pGd=Q=+EXJ1{w4!_ zD?0tj=6j6J8+=!z!595x*IsFMG3?qVFuGk8NMu!=_T5W_R+gciPL#B8}Ok zY~Z4XvDH)Ad?DslO{NGZ4$3-G_SK?>aX!TK?{lY*NQv;qjWjEt2+Y*hD+@u3iIL;l z#LfV0;uHp;$e%$DKd8YXa)IqaWC~je&F|c)L+)bxNhuc3T=0PGA2t(pR49XmKheI; zFPqFRFP!T@W33WZedWWy>!#1WPiNi6SHG$HGHkC@qRW%MlDX@zLs-F8ZQ&q2F~UkL-3Iy!#{7>|Ja>Enf)#2w}aO1Vmhw0wPdJ z$>3kPbY3kb&?3N20Rp%l_F?RVnQr`)dG6>(+uYvmuZxno>fx^_=wiM6g1?rId|#QO z63Cu_MJK8^B04B-vX?p6$gIBj{XcU@4!m!@E4@G94O-&GV)LUV)up$OR=-m}r|`QTO2p?OZ$3cWLFCqy65SdCTtCuh6+vzdeU z#JCS_9_uDeU99U-7kU2d(Zn7FU!=E;a`wJ9@g?U(GHCtC#`fohY(R34@(JFnzt8q- z^m$wV0|)uJK8qpZZi-UY=-3Lm%_#|49z;&8RYZmkAb@A17wTVBV>5QD8#8{IjIJHt z7SSV0%m#|(lvDOt8uhdKo^au82C>kYyUhvA1Lv6bnM9R+WL|(aoI7#U)gNGXc=iq! ziExq4Q%xpynxgVnD-%m}?#9(iky>i$ksE3@0$Akl2wz}ip+#ZTp20Em8OxFFKAe!*O-5abws8^#cnA!4R_cqt~-Tr#syz9X3?o_61`hxpa z(?gT>%wCTkG68fpdD+J=0`bu&Dh7-Gy0K9$u?6|VE6V8S(P{=P>KTo)DeCE%DRS_r zQKV+&=FO|t#2oTCEreiq^f-yV3>`5>P81UU*REdFn9+w4@EEd(AxLAkRSVN7eo=j* zeKyR5W$F{#o69`r2H5D}Rn@AM5|x@ZJg8^a)LN9D8gnUHhe&;o99x=!6G7K=bvqNv zsjX9;69E%|Z=jxH`)DIXCLibADCL$>U`%k%uU$T`U=H=yfNLB|wbZEUQAT0>q`CSY zt!?=CkR>iz?|lV%!WT-wBJ+dbPn~QBwOVtRKIwXTI^Dakd{YiDEl5HZqaSeTZg0t6 z?w8%I{dLWvRn=0AP= zOot%SNMepd8 zi#sNMP^J_pXCt@|z7yF)>;zeD=G97ioI|T%-IHHaaCGnXH%eCf?Sn-NNQ`Zr>qd{C zCZC(OTvB8%IaAAq(+f}Ed>}0;PpZ_OR=Bq_AG-$@2Qq4R{5yqUQJ}-ulZ3-RcA)q- zYs^fc`jrGwTEVv|PD$mnr`rt~HqwosG)Hs`)UMjkW3;>F40PV2XQQu8N+K#@Kc+{N z7G$Vt<6MQg{23ky%cW#Y_YVy`rx8VgVL_DpF)|uBok2}7fK$^r{e@A?IOyfdmfWG;!|&zN_=)+(Yl3M9pWp>)+Hy$<`GZB3(3*$8En`7c~A z1%ZXaVJnlN${)(?UNT-}zeZ1-At4H={3wM|;}onI0NOxal>$g)%7!$JRF5`M89=77$JHPYGattLv8aw8PH% zY>xtI9UTH)cdS$GDN>rYb|pIo{cM!<{{OPyv`lt3Io?GYBhD z(?}gHEld`!`m{T||2+W~>`CY+Iv}u^W&+fQdeNHC35+xjALT}mon~3ZAN-&0_($74 z!NK1pcZM=olpa7cWna%*_N2~U`r4}G12Cr~1v&`nI$-_)U-+GtY(NC(mYgQWW$FFD z?XI?;bz3+5z+Fel+ShI?!-+4YI)oktDJ`p5E)3FZZn3mpGOTC+p7>zYjxJpFi~<2W zH@~0`0%~JYRpX}3UE}60e^N@j^nWdNQ?jg({%rK{bdHu>WN`6-)y zE?`{@bBON72U4(@b9xkU4pANNw1)N(p>+oQeZV5dmW{y14PZxgimE9Y z?IyM@aAR6$yW<~ibH@&DSM=EW6MBIQFHN6BDeP1?XQoWVBEOyQ_)*+jwjw_4a^Nv! zwxEtcgOCbeZ(uR0n~+Q6eYjjS&aVXC8Kp4BgiJ&ba$y{;?FGt){0=7yWw4={v$wv! zQFS#a!&$#3T9Fv_4LT<3T}CDAmH-RJ)Kmz4kF>skQ5j&Ban!=xdS^A3@-9)6^&`T+ z19myY0Tfn)WSQrRoxdO~qUPr{Zg|T?MQ2g}B|1s}E$W-dxCZK*_bzP=D+wNi(JliP zIplC;$R?3V({u|UYfwrL4ZrX1h9USQ?~!KXZH)&t*eNrYxz@JDZpYRa6nQP$^QHSd z-6#Ef=B$I5nbUIXy01V%`~c-5s|s{=iDrfJ?Z|P{w9gQ`zEDX}q(0p%SS*P+1U6Xnx^MshAOJ~3K~z#| zBL@Z+vv;lJJWs%)bJ{Ba_l2uIBS3WO=x#N=KeT6)yLsbs=9~yry^wig9Vu&GOJB~x za^|PbUXv(P*A8mXKDu(z)WPXFeCqH{3C7h88su)>xbCT|54Z_a7KpiX{P1?E`d++v zMtTJFc|_<5e`xvrUzD2h=GVU?z{p-j@tr^-fetmK|M-|1*|WZ{U%jNgf%qW8YdHUu znUG<_ZUP(^uKu*UeBrcc-_%@k_Cv`qw;1*lf=A5RsbhQG;eE7^x}hAj#vvcg3aYt*#N*| z@X^rX7}VgFKlmjD4YsX+&Ye7pBCBaW5L^JjkDWNnz4P)vDxi`7xf7X1TCYr*u}ncL z04uhsl08*qQwqW2-2#e5zSk$2#r&j<>TkexlRk^7v+5(TIp>uPNevz9UeFSW@DM@4 zIe=2YpG3f7QWDoog7@qIy&0+;KpAx)7weC1(t!I>4ABb^u&}r>{ZEP%gset-z7ak571wAQ%*~ znc?5lj70KDJsTMrfEEraMdBzTS{xw{7Sn^!lZq0M$FuN%)PG6HX4FI-syNXcxHy;s zp&9QkIEofHDKw-Shu*alnIixK#pbLFn(zYXOQXBlJM=q?*5{`B<$NFm7JVy}rslCa zGyy~!nj6bF{E$T%r`V4$ zQ(BO{Da$P!iF@p zxR#NV+_ZUX)d2p$hi|HNL+E)p2->91^$unJ2*S{7l;9uxdg01XYmd^$kRg&KeeXu`QC^9DP});^he6Y)U^j9O>D#|qLfap;mv6*y`0he6U%lsj{cfpFX7aWCXGU%LH3sD)Y9E z7$*dMq~qW%CH4gBFY|75j*w4aOORDG4G5hlVkq3Sb~d@H+W6@2b*mL+*gcR|nZdZJ zZrKB0RLdS(2U%MzW5=QSL9Hr2+uP6oy?&SXdu|sj@~+q@RH3OCKeG2dF)b>$boTbW z`q~AIi{8Tyw_&`>_`o3 zkYfrAz^2-~`WmY08hUNDDvM22`NG*F?#%H60y^>BCo4Mi0VMm~JYE?S9A7y{idpb2 zYKDwv|A|>?SC2$kO zm_+SUoh6{r)CFxnT74sXg?VLvA*w~4CXLduHRc3%h*}D`lSAkMqJc#Z8r43hM@}>u z7lK~|#m=1ACr5nLxHdPjZIPUA`p-!yE$qo&z+zu}wq)M@c(9MxJobm`!3ULp{YzhW zNA_;c2AYx<8NXp*vA4~j^V<4vrnas3ip}_QS=Y2kfF*nLU>hlSA&~gcGyk=MaoBXI znbgjatqLV9*{oU?ELu=zh8x__B%v9yWji+gT*|i8$=B5zK;dkJ=G@TOqqk4+E3?Jfs`bq|D*tJ)8#8f+`fvgQ-+un@)Fz0};9Ie;#!sFrD(e0Z-?Cnc zv=u|0zP4U_4!=54?8Z%;C6O7(;dhEQUkQ0<8uhodTv!BkT+wH<>!) zc>?FWD|N}(MzjMEs6t2)z>i-ewpyr@CNtQB;7x;@yZk9PVe(wH=^=|2XHRucFBm8> zq@FJ8m90{p?0T)p*7tHg0N|O+1*@J>{WO`@&R_VGW`Hd+6|-^*u9 zpEnEV^5r{yKA)I?T@nGBHfN1%7~146oI5EN1_6%#GArV>k>A(ZXSquyVfQkMeJ+7d z@&lz{(Sx*5q;3tXZ80Q`jJuIC?vz9{3Sf3Xn;KrCn2EzsU9IdEDyRS!^~v(l@mTPr z@CEyzp?;EsQt7pML<*VN)EGGZcxBnJF^#@uKid3JpjE9ak{*y*Qo`q`V;E=P`PT-TM&uqVK+Km2+BVgUSUv)8z*SKFn48l2(au$HTw z_)P?h%q5P~gtqxwn`)Zu>4q_&OMy+82W_s>?4WI|bVrmqQ1Vn?eIo{oeNn9AJy$`n zgtdpWH)7Nz1t{2aM9--gCa@$GzoO`^#=?{aQTID@a=)BP%X-_IHX!PIi+U+|UnFGU zv9?}L6t+oC(1*1s5Hx7;FgavNU%TWzynPaU4Y1WlO!)yX5`jt~4v`!WU+Wd9qM`O$ zPJg#KbyjzX=uNlI2(p}JtE?uetK*hYOGS_Mwv*p^mBP?QLwmRmun0xm&K1s+_VcIQ z=&@4;hG{1tKpZ*4f!UCCl1hU!rI0R9)w6LY=!vsGUrL+T)KGiRw%3x{$!zF;U_jAU z`6m{muk>ikd@i3|@`qXP*Ye;o%2}5c4e4#9%4R0DeQT6yBBQrxHCa8&I`7*0vT6o{ zT?qAxMVUp`8fOfYL0C}iIr_XF*ztBEvJ_fl@xoA5xi1vZp-rQuQaYh+fxx8Bl`}_l zuFwMF%4O>P+qK`7d0hQzH)qi!?x63($r=&`*6%TbJ2a?2ePoY2ePW+2rx3JB>b=b} zvX6$hOmMRnKA_SRYG%)#{KzXLBUoImzO~clu66IPe@?a0MI}AGueDsZx2j5h#QYUc z3*173pEPZ;vWhQ!@6S|bq*4;OFE*>G6*21$h{e|cc=Oy-XRns;bmqif0deaYIaG5( zy{GCDJ32I$S1+EEz!w4I0R92j%kKXjDI|Ze@yGfOHp*(>k$k}Zkeq-KVJ+dHxrP=J zMdcrb3p)=IY#q6gIj z*rkj|Xum}b>GZj4^}dvSL3QmFC|1Ohv?$g){lShY-PCrVcEhesp42rp2Haxi+%*^Mr5!u)Q#;^?;+9H0x z>T%>S74$C(0uC9+*14Xl9@o&&qq>2J$SYw!i~FfYmTYgN8Iob&gsQ>OMoAqGeZ7kevYmQJ_Ov z4OAs-YV|JEixClq-a;J}^hed$N|3`Beis0SyooHyhL-~wq1m*na${R(iynxm4ToB# ze2_b4bU(Q*P|=mM+1YAQy8tr)g`@{wVe63C)wDHK2%rZH7Jb%Smo9+peI25`{2pKh ztAe%=I4WeJ&YeD-?6>%SiN)|v2TiCE!C`C=Ku{n`qBkbg5EM?iF2Sfkv10F-Ju;_= z{RcQyo1%tcqCNo}`5(e#C`R%lW$U0^sC^?Om^i8mE)n3V1ppdFR72+P5du~A9>%EP zPm_wb)&e2AANp8ghj5gVY^0w9IaOX+RoC@^6E*_b1#ATNi;@Rx9pa?+Xu-Pd9Ol7d zrL2^6KK%8n5aeidOYZw^w{Yb%8c*nMID01kmAb|0h8Xzn{j~s#{=Bz^P|zS!Tqk<)wq2--qcwwp}cOZsSN%S@55f6x$q&^+P2W` z-??4@lnlKkwM__a_L4`{)?(}1KTwdWzhE&x4+Nh=OA*?V&>t0$OcrSHyGuYQOa!*(pj1zMc`adHM2WzTr z<_b4?=5i^(qCT7WDc(MbZt7|KK~I8lC*VbShz09&E39mbe>Kj*duzJ7BtgR=#S5+(EF|lpFvfI?F zVxvlY&-ey?opaja-beClD=51baR&x&`EqZ44=h%`4DP}wt6HZnPJ+o8CM|;Q9@jX0 zq^M6S2KEa@07X_>@|Ot+O0obb9ICN00HDL#Hz)(yXb~Nxdp$KMPO+O2wBBG+QH|nJ zcVP_f;4SjUVU|`WPFSiNH%l-0~%h~C{h{z;ZOH=jm94mE(NVh%PZ6t%FL zYGoWyoMSB!p~J9eDH&zr)k&)WA9b#8Q2!_D#Rd;*6x9VueJIfaivF2;iS`1J)svng?V0;!nRo9gL=X$BO}pHO=Ygero7P3CdKU;O%owo0Jn=>9Fr zfUA{;uZNacgT!UbAq<&D6AlVJNDV9+urnbsz5~coM8B@V)i*S%ei_Og84?&Es%@^T z*S#zlMFun6r&eGw09EK>YL_DlswtqRV3BA(eR(ZvZcaBxhKW^#TE)OxNT}pq85-v} z1aWkq?hcJ9W67CfEr06toTrcNRW_*{Wh>s>y@ADi<~eq(aR5$1vA%F;E_~3fdgS*d z8iI1~<~P3M&YwOa3U2XF-esyJqiI))Pm$b8AAps({jZc{7Q?#FIm_8Q^|`ysK3K0{ z(fbN~nR0@4pZYg$%JgOKV*4r4PIqs4NfhN!K4G9Br>Yqdve}QYO~}M>PJFa`gX&?) z`f>iS?f?~`-?RlG349_z)#PR`dPvmOeLLS)-73Khf-xwgvQ_|)&{&tO`@HIp0gmr) zcuv71GF+^03I0Kk?6{>&+vsuA1OQ>v$Qf6*&Y$g7mNgvLI>*gf`j~1Xsf&ZkA1Jqc zmVLft&F6Lgp}0!j^X-5|0#)N$XS?|;Kc#(778IZgK!4?jf8mbo+hV{s_y)Pz#RiZ` zM4$#R$XG+$y>a!TJ9==N-VwIIb!B1em1HpWWLk!d5Q~k>KKE5iv5uSa4R|Jk&3m@J zB25hDt@Gw}l|U&u;q4c80~%;omz}?A^+O`V`+bo3zI6 z6j-!`Pi;~{ktBX{^z;6`Lpc+gvwppt>v!aS_b$@w2vkj;zN`mh%7NH4VzeA;Y7g1? z7_X4tRs=+9n?!1SVyHkYBJ{;E6+3fUQ0&71&>u^OAxfy;8IhCWTRrHWon)Ep0KQ`p zio3K3N*&Q~W54LjL~uflP5NmMN+PhRD7u)IHa5^&IIzh2YOK5io*F$UE1Hn%7&Vz@BE)D@sMh9e2U;ZVrWN8UjTnZ)oOiLikGhfwg&J(L~vH3$^q zOZ12uguz2y``IIMEHT*DdL#u`7Q+w!KZ2a?uc zL{}>Yi&^(Eaec}}yAn|84S(1N^rGUOj_%v+Zr%*_3IDplVrKj0`uXJp3b`GVd^H0& zZwD+!5z;>0*-F5oEhfvNP)Af(uev$IhE-f+%PfFvtJW>b;#gi35#$;7Akl$Ah5B|Cs4Ym_NiC!vR$ z0Z!4ze8cRJ#Z=8#{a`&4c7pGcHA2-HAdX{c&Yc&$iU!v9c9ssGANRN}GhJ|&$z@zo zZ(Z})AE+NIncjC_{U>+&*q(&SR+LvPJ-sRii+Aa`Ds!9C{9j>4Fhj#DvS$N7y~~2d zL^<60eJ)!4Ik)t_-x5G*KX=USeD6hfXz!*ZK%(^o<0n3UJk2-sHD)ih%~~OK&tnHa z(D$YA-ou$lfTYfZ-V{U+fj%-oRjzH;D)r1|kMG#>yt{eriqG`dxZ1ip^$?_<5#bs@ zEoT`30-%GB1%314xs&d~xug0!Vo(5%sdHATO%7|@DEd$gttA%A9O0^Y%bpMz-M9S> zck;+i{~4KXrmG=jz)86Fbx#Mo+n5nuBK%Ag(7z=zHlvSax23x|LQG#Rl@wL|RjtJ{J|2~nu z54GEY*)e0@eX1Wlv~RQ9{XU{?H@#m*X#h0(n{Mus$K2$Z%iOjN&$$yvcIhNb{HP=o z-=7ds7A)fTP)|+WDvH3WyEO-~m^~AIS7Z$$aFzttquSFXNn{??ohQ%V%PjtKkAmFY zt0vD_)`P)>M{bSUZ)j1=Fd64hhqFXUoKxyQO?rpr640Xolt4Gt66)@@D6pEuds>mF z{!y1BB|L#rqm`J`VFqvD$IV?H;}G>LQNv3JsP;fbU@@VsriM9D5liYHQ-IDD1MmOF zwTr6L3D-_)^oYV&Rm=Eh3ffisLsM;QdMk>AH}G;qy+g`10izhZA;U&kO+`(Oy9o^h zFy9O4OC)$|;f6>sK#EecL=3G|pYNpOZI!@m(qfi*}X}d9INF!jzfI74e3G=-t^nwm8!v z>CfSE$8O*M3x)P2aV1OQ$d@CjWp7gm@cMD6B*B!V=inU}JHMt0u&{#Z~N=+!a46O(mRnLPpBP)66%E>tTxErfvA4G#zJ5(d@r=A z5g_aAP@hBO=C8D$kpKO-fD|JTf0!~@SE$Hc%c?_zBDnszk z6zJjrJPFhAXNL)JU`Iri^)=C|FCt6nX|Avy$OQ1iyQ(&xvq$}7hiO0Kcq^EcFeDyya-AzP$gkA={d(t}^ubE$ z|85)5H~OT2nt>~=6D~Ou27Y>%JcGYq2#4jrk}YR^fe@i z(qnyi(w-+?o=$X~vf zSsai}zf)gQ%_0$IBDX}0adxzMFQ50Br#eM&SnSld5&cR85(-k!VROqM`DjL{ZRC4F z1V@GCLx!tn#f)8uj;C3l+u1aCYJe)bj(1jK{(H9ht=~Llz+&M&@)XsS>nrDJ(4Yn# zGO=Q5xTgxdtDFbn-U;y=4bV^DC-L^BS{M$Gl*Y3bObaz!(6p zvKTc+-JxxWr=bO7#R0}TBExKTu9lTBA&`kO;836GXO&Pj{k3DaE{HEBHEcec$G8k{ z9_JN!hwFKXf~wt%>Ju#pVdt5F!~h;*5Ms%YP;VL=$KGhD={R%9ahOe;vs#B8QDSpy z^I6g4Y3!MNlVBWh9YTJ+O^E#GV`GX7`@4Y1603T;Av zz+!aWJ2GlMqlXiR6VNhhq5?9iQ9O0fU89d_B4X9s2v#YpIBEJ~?Q44XAt4`}7$W0Z zK+vju?IL~LT#dAhHL|hO6EfTBlm=0pYVCV${kVyt|P`K$R2;`Hp9iXg3Du&u??QwzQ5maATW&j+u%Q%Cn0-84iAIU9vf46s<;aJAYWkVPW1 zxOe;O+N-kNs`KUUsVEffa#lX_6*p|yNVoBgZ@J4C&bXNi9@JTM_@k|AsnIfelCo^H z@3?;bveq6dpojKucGoYTch|39()q=TAhWk%#nbvb>Yo50f1>$6xwmr-Lz>-+hrgs6 zz|F6J+xIH;tG=IL5nAoywVzij4pd5^WJ3vs`uW;V{z~_-I!Rwzk_#r-zgH`($X=$_ z5<2R>4__Dfq&!LL(7FZ`djt8Y2u)-g;!K=>W5y66FMQY#^d^XK>eyaAGnrcGx&U$P z@}>5Vbq{RoZIPR^$Jr^9NIOtgS6SljGv*yklsNmn0D2!e$Zfn0HPJai6$b3bHgTJW0Z4j zIi{(Fqy2_O!F^uR*Y;o#Fnl5Fq@z7oV^GJTX@IJt{)uOgxJwt#c!2<$iG)rOdNg_fLp`YVjq{S)w*eOUD&Ut|#Y6kvbC=Ga z^7|u8rwzG|U~DD5J*Yu77sOF>J8R+5C=Z@)(y3*&Db3R+2V6pGaqWNLP z{Vw}_oPI_nnUl=k&E3F$Z?f#{7urHJqk39htrjo4@aDJx03ZNKL_t(%PaV?!alWO5 z1;z7iD!lxIZwOAKZiET0UT${>cfaGVTsddiG+)=E5fWGg%v6i*5duRz3xT(Az?=9B zd(5KqJeO#7taIO(nhYQN0Sa88{#z@IbS_N3e~@~qEnf3kIaG46q-t%nQL=@4Mm4{- zM%uC!uts#YSdAtB#t)7mzYBj4&WB|V%u(cfreJ7w)PQjUSWx$j)=LYW+#1Wzae-)3 z_(pGF5&9|iZpqruyM?Qs(KBpW|9!XZogb@)JJg-_4y?kijMsHBd@6sPPi$wG-7Xb@ z#pK)JG*3r$pa3y_pn|Yb#A$}wi5l(l2fm~r#Q8Ia+|I2p30RStA_EOQI?Jf>Wg0M~ zd`6ynN3vy5#>q;4v}?V)2}>tpz7z?c5s(};Zn}CU5==#b6A`%N4E8Sq6Q{1OL2VS~ zFMmocHTLg(OIbtObkO(k_~9L@XB;+sq|QHT_{f3*d;qPSkAPvAF;_00bJwr6t4$0_ z(zMs0AEWkRq!D0&`D$Hb<%3_AGV9j2zo%>2Gv@7bdXi>;2Za|vRV@J-dLa_TZ5};Q zfCSt2`j7ugJskCuD=*NUl;Ne0u1@|0fhTD1fMo=Jjvm;mxspA&Wp&8mjD}T^1a1Af zU9>h8OscKde&xNdU&VjukPQ6JFM`i4?KR@5CCf+S*Oiv#0^5um;%EcJXAL`BM?G~QA_!T<^}LYD0@X?5!Fg3Zr9hT6dA9*gW*J8}xnHirPSUeUQGJ=_h=Q5Yj`_ZvIY4Q5 zmuqSsqi7(7^w4F3184`8&&0`>H!%%UNK7+%d_=P2K6-~dHgyMbUc0(Plc7<)DIl6U zV>!C3KT(pQ3Dti{CqMKud~ z&=x;OpvZ7N9GbRS%N>ewM-FU>#GuN7MSB(X@fzAJiXVTXj>msPpT$9krpNnPPrB4V z-@b7!0%|t?8Jf(17O#D&_sn8tE^6WUSNcq!1Xz@i#1PR=$qwM`w4XhxS~}=(VSQM} zFDdo*M0U|%#gjZ)TN%=qcr3(!~3p8iOYe5)Pzdo^Uy0gSZ3F8^#ur_$$DjI>Zox7 zVWBW4){D+)n_OF&$s5-d2qBOdR80j_rJij{+kBTZ2^&WJF`3qrM|NpX6#XQ%$4QW* zHy9SL%QW|BqCvH8-m)j%iif_WeYkh~8}6N#|4|HuG~5|i=@dOp_+;LZiq3;%C6r&p zy#*{PUHbj`TxB~kT=C9>#lri`?=a@k#I}X*{-^(~dJ9ACC#y$xkIa#py(7$b`GU`+ z`RDY?)CzpSpz7>&<0j3PY9*Pbo$o#GgNj`eSW|W!T69$JXq3nvfgS47s4d*_-t$(w z8d|?7qiA$+)-{yC`=0!-q$K>-3xBV3W%iQCw7<8${e274sLY3;Q;mY0sDQVOo~Y6c zo)r*DAk>6*x8H@OM=Lv3=7|d|6Q`l#jizf197a6O0%bwDIqq6z>Pybq400{_#-AGX zw5P}2x^X43Ay#MV6_>p&OWliL1*5aimq}4;4M<|w;YTQ-ruuH|62e}CT;tFd(fpyS z0@(KNd|PwP*$)tgu@L;55ctpNG8BTBDmP~0OtCJ`ojL4wZGA~LI|L76K{MuL`Gdcs z8dri(szjY5R_IDJ2V?JLsdB*Y{ zA|BnHH$|DkDDh(yA#?HKqrqGe+pKIpgbzr)Cy|s~(^reI4HhsQJb0KcC+ElazcCSm zEN}bQ7A$6Hxp}9cOwD4YOQ{@SET94hkQJhg{HZ7wnMKjWEUTBDU7yia>l11l$y(GX z;wJ&5!9z5UIBLvah?WJgDEhI~OoOz43Lq1zCq6ASRYg%J2`qBhq58(5lZYb)+FmAt z7gPtW7R6k#DmQGzDAzK^gluqHRiAk7m=5G1C{jXG^JB?-Q4=y^WUCqrlK~{V8QKQK zf(AIQ>5NpeV$i}E~)6__tH3pbbMiJ_1u#)k8GfV-qc?|X7AwwmeGJM2XIWq(~ zu3l+(r;hG)7tfw>H*Q|F>|J0mpm3_btG*>gFf|^KvazY#vJ9VzTuC(*AmqWOeuuDw zf^}&|Qh?1rr)48?rbfDD>kzk?to@3k1^BaIpVd1i?KqDQS-5K>gA|eJ-mO5+xgxL2^CX)7Y7fq%wk0S zRscZflC3KM*xaR$i8fBl3F_uplUi@S4|KvZiRiC@ky#5Lc9Ul;bH@(8udJHRM_+df zKm_~|WC!>ySow^Al@l4 z&Fg7{L8%7d3Sk`TBoU({+m5{mpo{fF_Hx<%Uv!5LY;}9Ly^{1YEzK;JUmNVrsk2tO z*^3`m@D=vN^m*%)?R@n||JfbfyD?=ldU3)AMUbtjMPmZETA9(CNh zmIR0ycLGtN1zS=o5?E;wfJ_u26x^jv5bT2?@*`m8$kz2ZT@O|qV>e;)JY{zQQk19= zq@%|seKRQ+!1hAzy>jWi{zU8umQ<=N9|90YjfDwBrkge*sL~$Zx5e9POcsH>)Z$R5 zxoGug1myN?dpVo+OUAFiyWRE-z6lv$GUoUS+(SNJ6zs0t3Zy}nQgd0bcSA{!|8Rfb zpzL$q%PjVL%09_2RJBfB(nFRgM4N+1N}}|XxqG1Und2@g^SU}2%T9ax*acvh z^`&`wYo@K*qq;%*EXGolR?WAyyr5>v8gu(hnI!M6W+U`d)3yDx#-bt|K-3jd4+N!) zgRZ0Fx`_igD>zTTYY}D3dZYk{`vRi4PRr;iidu5mpES-h|Yp<443>M#k6Kw&A3#)c!oGCFNDm&?gLc3^8HI$~EXbe$qfuZGb9 zV(T?u9Dq2m)?W%iks3Mdw-Zna&!1B9(q{{qet;qkr^%dgXsTykA~KM^M+)3~-)JEw zT=*%!HrexOwp$}#+3u|bMD`Ob>fV{#2T*KOBy1)CuVw5MM_)wiqewRUlCMowN9f2d zswgj$EjM;jwWCc9jud@Bp-hn(Vc!8dQAE6S?xeeh7)EGj?=#B^mnaifV*!)|2wJNE z){z9M2*%ZT8fp$KCVdlg?QVE3sM%x%M~|Q8Ry_D+?KxA5>=qbQS%RyQU=7c~zEi_% zUz^Bx4Fp0f?GU)^xOpQ{KCJSBTM`lR43nB#&I%_wI^V-i@DB(^5U~$+j~Y5Z@5*p$ zHc0Bm^iAKa0Tw%R!6R%EYhI>|v6!qe<|*~cos zn`dDq;5B{RQm|ObhAsC#$-NT>Q##_Xljg5_#w}X;8J#@@sJFiTUDc%-1IFLk*BOSu zO4uJJ`qHQw96xEEo3UV>GC{O_;QPjG0W5YTVk)sxvqW{;7Pz_eV!VFI?b!SaiKt*F znPL1G)yz@j-*Hp@^vEi5y^XJZQv!lh5vAF?S;8~`kl`aIC`*XAO$fS#F`zdvzy;AM z{tflhwpptMQVEEX-Gj19=8t;-8fmL_@xp2C6IxU7osV{HaQi-dGm|B)WRBQNEo0l< z3h2IFw`AKywH!Xm?Rf76_wo<_Li1oXhUs1m|1GdsgCgu8F_MOl9H#&(=NYw*WEHKX z#TZCxWu?07h*{*XtIVxu8t7&@syuTnQNG$b%P!KY#|z;IIC^?%eZx@IlwZGgS$2&1 zW-U?&4Y*fZj-eyOuB&foaM!O~a@VdxRXyp>pFJj_GR|JEhs|XUM~|ECmOo^a=#8&^ z%P7gAI^WYzL;2P8`46~R3mIRveT~pv{e4yI^rbySc!R(U#tvE@purjrM=5`QT&9_# zz88gDEI;W01+qyd9gT!KO>+T@*h%CZ#7~K`TwR%0maDF*a*a)+T|>h#IgU_= zprUc`VT7qe3QgKe=*&J!hqDMRhgy@7qbKPwqTLJ5Iz~P2hZP&jm?CU0j@6s-EWCmG zdv+tr(o#$brRxQ$o)w zQM41q#}rZxbW!HPqE?Kj2=dz|q zn~WV<6Qbfcne2({S1u+F2>}WO3ka@+@&M~sX!KD9Xd+~50Xtv&mjpa46B%a~xsTDs zL#?g>VcW_k0Ks0HF@K$#yYvY;rIzip9*b5BX?2kNJ!BghHO>!F*?s2H6jZM%`+an1)M=f`!@VDb1Jn1vpclOr5>P9XYVojh{Tn&0h4V zGIB5d@Gqs-ti2n0Z$~y$Z{dZh8XAYWAw!zo$Z=ELnDH~+sbjm8eIo!GYNZiaWDLR~ zsZkHXpB|Lkud7YRj0N}0E>aU1Q-lfDVNXy2#g>{fE49^EMb*80`K*9E`y?Aa5#;Tb5loJO@9Q5?CC-aNr2F=l;VR5F?V1WTa zt1Ad`<+3I&%)2rhwW>4W9z;Gx=LD<`X%Za>ql}@IyXR>Qw#E$9NgRiaW>2>pHMT8L zKWjgCLI(m4oz*(TSx7%n`PL>Oc%fQ`24#F|>IX|$rf%>McT*s?O9wF-4l*c2kdusF zq}&^(B4j2wT=_wKKx;eqJiUU&qIr$7C+U&mGp^A%^~X$?%|`b)H)zOEHGEdvm98## z?b=0m<>DEOAgi8){fc6o&njo0p?}9j>Kqz4q4fld%Ia{!TJvw+n@#8^Sj^8s$@v_sgq0?Okv@{JLtJ*k3T*gkC?FJ1RYE)K{ z0%!m7&a|gN9$+UrM0d;x@v9X zYqqoxyX1tfc<@VZ!sPjKl7a%WIq^n=Wq&C1Of(<%0sr%0m3#0Utfy<2+f79^X^rID z^#lGaWyR9XhK<3#tbXJxs$=6twyyty>dJ23 zKmi&mueA~hU@=$eopq3+^;i=0O5CYj*17P!t~gv$*=b+lr^=6G>GKR^%roaoVn>Wo zVVlQ~jqI$GILXR~f6ukeT%n)|b%KZu;SlS5@WHg0mS~sZdKQof*O|TWVK;2VSOKWx zhdwlb*wd3_nL_ssR|iQv43i7^?UX=XVcWV_euHnz|QsV;GTCB zuv9Rnrbe}qHPv;p+qASG=*0g}VeRhebX(Uyr}3)fC+s7}02(WlNuG;7hV&WbJlwtY zW%ue&{Y^T#?{zwyiJB`yuBN5FP9`^6{XW7XhnJ02TV1aRc|HVDjxzYKaIO*JLfo zH~`qLUi#RpvsyMHxZ9x_G0r1xT@U~ObV6stSs+4q?b3zPa8}L;TDBz3VC(%j=shTb zP7T!zs*`HucoA6a=JR7+>-44W#GxH3mgmqjXFY}v1++AuS4`{x!n3CjJNlj4HcHo5?-`o- zwR+?X7z&u(fKn+RhN~r4WQa)*Z6G% zMf$uB8ltE_O~HLseIr5s-1-c z28&T3G0->!7844FZ$@8JtE@I6D>%T|hTZSKtl(l;+h)tL71?oA00e=(K@DnBPv&XT z^rdQ64(Pgm)hOfaEkv0ND8|>YtRi*9OV<6i_7uV_1SqKuqp>_$KYlnfaMGcOk^!B! z{7GdH$sqB4GFF@4__jN^d!v92wR_Yi5;#5g@ey}y|NBW@9eb#=t4qLxKoH59N8&bSX)2D9oe@@HJnd<@xRyj?%MjIDW~=z#CTryg{Xk8ef*C_ z1wDOqm)e`GdE~3o;duKOf9n?C_jxya(If7IcYf&h?_948A1z2WzwsTnZ^xSgfnz7m zvf#1n(YuctJJr4VV*|!Kn+XsNlfB^g0KcKb$0(Ca2@Lh>DAw|BtOwP1t9N9z^atqI zO5o|8m;Whg6_VZ0W>fk{=j>4ce#)#>uAyP57%s;TZ8x8z&q>cSZhEmU@wNH`FmK0T z^%E?bJ?%F-xt%BcHTdqG1JPBp7eA`2vA}VFFjQ(H-OEDj_jE*H(QJxk6cf6LAM%)1 zR4k_PYcMx=>Jcm1=mPnChG1Ay4`S~p}^vkonj>(++S@x;%D;)$%Hzb8#!*O8#7_1tFJd@-H%Tl)L{c< zw$L#40T!iJ7S(TgJEO>A5O-3vQ52agmQ9P=C1j@AAG8xD&2vMVT10P3+5$v#R2D!a zV`qwgCE3x6z~TTMPCpLNa9U?95deS^gbfJURQ1=?kM+8fu!;6>N>a~f=ZfAn`HX*` zg25WED}1lu!tHAY}qA zc))uj_=95Ju|cjV)iNkKgo2dw?P^{EU%(Y8?*EZ#OybXB65 zPoI0ATlL6SUCZcJcWCcMx8db)h~PalzD^3|*DUN8)qAq&7I&U?;D zi&+xoj)s1pr+4a%xdYcp-cRRMWD$CCRx{^*#88Os0UM~hyTgqfH_bir+5c9VpmS%A zxLsRbu$n*YzE>Yr(4oed4{5s#+k-)vY}B}^ZrYqR?&5`0q83x%N7(>v!I(exmHK(A zeh!K?85;|r&R_PFo4()y*Z%QQ_1Yw3N9Kw8*5e1a>)z~}vnM~2pv(iG`Zr=4oI1Ko z*(m~$oS&Os{if7O2}%G?5Ln@NWCWqql0j!bs$Ti(B>@xe1KpH5L9TB#ebn#;d!P2> zRh?jUom;TtDK~oJOeu4oIP_uEKh=YSBHtn@m8cdtT)6r(0%nZY+Q zG`6S7{jlaS?v0=PwN%`n{?h*-W)WbYj4G{$uzj0e|Bh5Z0b}pI@g4hpZJoRC$**ah zKm}$E;WyA161&noy45}QTmQiw+Vig4^v1uqC2O8l_7OWuS(eHI8iu)FeCL0Yu0rq+ zY|YiUmNApug5{rbLr09!yZ|PxezRNlj(21}FJC_AZeG2tY%w~i5RcP zknF>OfJNs};(3Xp;}pq{Z=I`5Cp}6{%`I!(iil@CgKBrBF4-Zq$PhUW4SS0~^Z-{? z^0f?@>8a9Ojh;B&T|R%>b@gNm&v8%akVLQn@?`0>RT0+c>NFZCnY)|Jmno6*Z$SkR zCke+JCr33#RfsuRYb4e>&L?|BwrH=QdP6^5! z*(IDvo>i)j1^sG+gVWa&-p+Y?yLMpU-?xZh3Wft~#jp8Z!D86kp`T2)$+v(vwZVfM z-17T>$IV^(xNARmQtcXcZ+$^y_Sv!k03ZNKL_t&;F0+Z%VyqBEY-$;&xoJOpT!9Ac zIkZ6pqX=@MsLL9KUJL*l-#SOOhKwV7j;wjx?3Ky}o;kiZ5mG|vi2Dy6K2~Kp8(#Vc zy)%6WZ*^RE2X}4|#c=-eCv`7uKhN{Q#-C_!pq|QEbEW-b_s%QdkPSg;clQUcx}*Ew z(=*Op_N3Se8(;sn&bQEm6x!>YC66ncx^v453Sd}Z)-xD9Ko92wdx-4V(sjSBKq?@~ z+RUU1$3=nFxE`HM`n=^&s1$*gB-7@uadVeEt}%M~M}O%K?s`XSJ#E=z0*0b}PF>^{ zul|exG>`uMdU)n5|C8>u>Gf}^|7`1wWm0ElP6*_zc<9RlwFL3_lbTSn z(44D}|JHv{s}t&wJ8#j_r`|pNd;g=mbncYfx%GK>|5JbBP8{B)U=e->ARQIjpMCp( z(f&{DxdK+zZfxruw|MR6)TV3a)))0104C=-wgTWx29mkN4swo?)jqs$lYoEbOwWPE z%J(FKg!Qg<+9I75*dkO=lZ<&L&lXbl`Ky=v_i#A>5`FS}nZ?SNLYYtAQLs35_G(#o z^+A*!vc6ks9YFdNw|%HZ8Is!`h2QiGRN?@a0o1)Y>lxEfl*Nk2HEQAuXjCnMWWuAL zq`t%=Zl*Ab-2NCjx@4%XU2V^aQ`oimywz2ibbm^%F$0CN7i}@fyzqIVjyST2PsG%; zUY9})7K0!NGVH@gDVsw*hU%~)XF34rgq9T47W2-3$dL8)xbaiwxnWJCRjU~KJe7N{ zcz&QHkmWDR9s1Z8fH^p8=pl%3A;nZ7J?u?@Ej3=}@ z1V*5>lBH85UoAZ7cREDQt+g_s<|cJ=OR|by6s<2H=DoZWEJphXXOdoY)T2R<$LYk; z#X%lBakie3%mfZ6@7e?#Vpxl(9`@+{P{gDsCMt*>oi{Ad6Rj(qr^!PUuY}t^SNpT^ z@7QNkHzWks0%Is0^W4p%vm(wy%Fad^MlyPg_te>|RjUZ?`PhMNZrg?*x^o{NwlV-z zcZKcul)jHyv$rYO+z`cM8^f@o_V{e4Fh^Gg>_y2Jb4 z)0$rO$XDFKJ)7MA58u!_rnV8_1?`)lCz=i$U;Afeja1L>#hM8AEm`}lfE~5~@f&*h zO`Ee;XBSy6dO1=%hpO=O`Rm*(&;5neb_onYha@wE!YIIs@g!)n{DCj3H{tsmp3|Pt zkEhMrf19pAunj!Nf>qC`-f;W7Kb3-TsQru2kNgsd1CI z^y@pbR_|pN`)$4NC|H~{ZHXroh8&U?2+28McjQ1T8!6}`y3y|;`VII(B@S>u!D4||R!VAE>1 z77FY+WXYmPJx#W`d{!xTa5><)uTclB&WmU{N_M2OTi z-z%%k<7sAS%J-?z)>t={$8WjV#BtPKdLRt5q`k%;}rC-+-jPqpnm?MDI>0b+$^ z8KEXOea>2U{P1?It%a*Ut9=1rY#iR=8XH^G#)6uzM?U-SG?$xS|BgEisOs)?6WSJO z{w|z3V%fr#Piu||7C^7WA>Z)Q*99I$K(4NmC>Qj3M4+Hw62#f~+P76=F>dl)38!4X zc-n1v=^F};AkxA+z3~72N9{9SXu-;-m8qo3{qchzC}>2+44VMu7BCdpUYWHFgU4s~ zS<_@e0X?UW?-Mu;f^VttRl%9$1EKte{k~-F=UwxtiK4I)z*@BCv(m75`3HaQ4(xg- zsi_N@-EcmlM*y$~;J^IbpNqNBHfxoeJad_9{s>l)^~67*y~nl7=k$A&VqgF1|D&41 zIg1~a(kvo2>^1Dx$-_I8rDTjh^`-xxz4wl?>$=W7&#QzgFKp*x;?gJx0CFV$1R7JWr-ri96%Bb$T{bnGYYv1RkMEI zKIh(Z?|ZKT0E&{DZ!Hi+)qD5dd%`~Z+xy$!{@-Lrc5GOxvz&kw<9=k{CU^eK5jX## zuZq%&J-l|U!S(5n?H(<#I&92zjmfct+hlK!9@yj__~frEa7I1ypkWgPutO7~AIG^!D8k-ue9@+Bq5DPOl#UM}Dx8s?AqYkvY@(R?Vu zDDR+`FjZ~bhX9MGV9|1c`b3Q8l?$g0*p;}pNunFbNgQpIc-08L#v1qn6ub2mEi1hDmcvF-*B9;I*BALpXdD(WOo-#xc5Q>%thM9W>R8W*p zO(!5Mp~*#5)$p;R4a|25V4A=K_eWN?bN4=Sz;S#+Ce;95jjs`_wHm{#^oDFb;F90h zY8YH7NJs?7ma!f-W`?4^(74E=ai|)-klv1$1wceURQnJM0HpCtb9>F1(ZhJkl)tac z(u$#CX;A$W1B)frH{(KGB0Us2=tVs}cS0FOlXy?kpFS>NdnmS%ZDo_fS|D4|rF(BT zYQjANUS!lv7@^TsSJ$atiL3_e!Frq;?GtAN0B0>Ja5|l*s6tnzMa5OGE@=*>L}vv4 zD|N3pNX(^W!U_&xjDy>~M}O5BkvR?2DjY#TA5JJ#O+a9;{=-GLWBm|42ka3FL1w zj8XWYw$E7jX*YA>GXl?K2cVyJ?>)ecpSoDtCLGc+lNO3v2w22{Rd!Q=w^B8%*1n*> zoNIzwWVPrQOLmxRK%FGxrItXxp49Fy3e0AxVjuCD)1j|7D;DYx2M?R*3RP7CJ1EC0 zh?QqzggM9sX8>JczvGM4)O2xk7k^O>JL?n$Q2-lYoa}fA7_eu^2EO;oU+a6Zo9rQT z+$%&SM#!XFkA7lHbn7udA~UFpE`I780{HK}{B0?ra!qWV=I2(E0veO&e8TP8_?E!r zl(|nxs09jS!-dlVZ-BZH93=HV8^km$%X_-_r7eDoz zuBNumz4@bWDGy_>6(R+y6V35gVKA8*VY}L}gmwn>j zoXPVZ`l2B&hpVHc* zHzolLRBgjL9X)Y@f)~3sznz?i%m?;7jX_%GmHC8b%iL~W{gMKBX5$c4iZ@-yylmDx z3^IA(0!=2H|V&3d#2#{h8xG7Kgq zo$Y%Vt{s+M{=3>-;zjgR=v`gS@#GNw89gwA!<^gkw>cHLkF^IZ>SQZ+w%f{Rg!`2! zfNz*>#;b%{YHLp;dg3j~WYe&|Yqvg0ls!l{2f>y=SBbM=F+~d}7I7J9cO1G#0lTg! zFOfUMGBN^4?H%Qah8jEcs;>&aYi<@T2B0d+iKo`Ys;uR{j8l^P}fEG}c>S^4XB|EC|)3p~YQn%ZC;0QGe=Q|mH4t%2O0758q zsPK_#C!nD~L1mSzEL6FQYW8o7_8|9ZqBUfHZwM>`!cYyio{YDA5TsxnF-IdRq!34|QpyH1of);L+qxZhlUs?j000p5s-Lt_*+9S}^f>C4aB$bW`%muN38MifnH|4waFUrHGV|195-c-t4|TX8 zut<$788<*QnP98=F3&v3%3Q>w5Qk^lI)zK`toCOv+A^?qePx7QiyJy(iZbNXrb$_} z-E-sHy7)RpY%(kjGKP#1R7#wDz)z?-50vC_(-*60{A)k_1JSA#^r)&)@M6HQ2?Al9 zNn{eq45O;LY31{7&(`+^7SEnMDC)5Zn%RqM5C9=dh2kYm?fE{kH`G3IFJ$`ITZ2bT z5g^6>qIgR1V9T19wJ!oq9|4s2Uj8f9NfPjR;8Xuf?|b7%-*ne6U(oj=cvC-Vk$de2 zf1vv$(+FLgfCcw%{+JJ}CdD55Ng(GwTB9UESgS}L}|YAcVpWiS1On|=Qm1pHq6=RZ&>2hT<}j%@9!xBgzV zPx@REe1Z z3wE)dC@0`^tRL`Mw0z0#?~d$G#$b3oW87Qgg8yN?LVfT*;&YX|?#E!UEj#zK z{rkHL7AMYnqy>XdRQWQh0MQ9bg3~gL}on7V9}Ig!;AW!dmjFp>pyh7yKwr5 zd-v79QXMLp9OiyIZ5a-4*Jp4}5%)0%bWaL^lv(jt3=vy0{?&l)T31)sP5YO?msAxy zb&&%H#qHwxWA5a!J?_%k;{x@}aX!YA&yc2L(E3I%xdk(4Wt(B$4xFsE!U+^YnMNRp zmIwQ`uh6q91DM|7{`M!0{+O1Ej{kF`$kf8y8NmensMnMLN5tT6!=_70!to~e%; zGkKwC;3x{?A3>+&8k<(Upx%9b28_}gK67fHYr1(;^^wO9Zda`zdm4}jki>q!|LXs% zd*ZB^I`5NG--UX~9zjH9(PO`?J+$oQZ!1fU;LW*H2bG0_#bI{a)^Xz8do~Z{2xQq< zzt{{K!#5yC<@G0$qsIf`B-r7z^qg_5`w7z@)-xa8w_YtbplEU)?B4pGTl(CeSfI?e zj!Mtqpgmw2G_r^@7koy*jXlqGVGL|q^`fo`7=@-w8;rwy)~PPPN3X$ZUomp*Y&UxH zz3$Ct|HvKQvtF!&dmjF(sI`3mgz1X~?g$)HcSs+}A){vq9MdX;`QUp=KH!6}R%pFJ zF!a#gb-E7#Jjs|+VWgV1Ixd#(_jmAif8O6-7%_HE3q5df7y%7e zBwc(tp;W~NzuZyP(IY4!Q}{!i=$K)EcB&u#ywA!VK3{wwr05{)N(d}a|Ku|h?fuH& z&I7Edt%K5q0VUF^%oDQXarP+M@Fi;^T|rJOK#{*$0+-I8QloPswwWwcV#|f z0W54GP6p1-rE|wcfd=%%JrwOQE}t1{?_T14%;m89nMu=U?tx4%v^lbTtV=0zB4ooK z`XQofT2-xi2TTG`$U-{bd(9;D2?A87cN*;%iQp6}T&LR3T2llg)c(R16d<4$2>KuE z@63t)`a@8H?;JLInjCo?U#T5S{jXN)gfyi_k(I{fWO|6I;}CMTP_KkyFj+(dKn4w; zq|6L7F0u=OmL6|2-=oGEVKwT|VxV{5Ms0ZGN@pIjkOXpO7#(maLUL-cd z&dqPD{wV+iWd!PHx(&;plR!tdtxZg`_A_o9T|kMk0(8`N?&`Yt7@*ou#(*FXW57OB z#_{4AWmL(=lJQ6=+;$-5mQp*SLai>oj-J%5TM^k2Xm>5mq5#5#AoFH{#Oh*(QjyK} zZAS`DnQ`WN=AviZq?wPnOBYWmo3(rMGVQ-oX9x9!fJML_RLLH_2Wm|n*s)TAREW-O zTKS?oxM!_ImBvh3AOWKt8{SZx1?u6bFQlI=;w$tDo)GrXxnra{Y$Zi-HQUB-lVpC}^C3)s;)Xs{kl{c(n*a-~aBJJTSG9hPE}cJTqI|Wd zky;SN`U#`ZO0U#yYhQ6w=6+Jwynf|^d;Qrz5;(>N#X>kCFh#JcvfA2Nv0PCJow?xC zuJ?f9?&Oi(3Pz!3N(&Eyoa}ojo&ZSdLlGxBdvd?7PrV~RkBl#4kKheKsbw$yrFtv_ zqS-r$YxN&e?=D?9EigwtB4R`+C{s&Htua|m>=J@J4d+j24RD?TfC*A@Z#-+mrPJDz z6K6akkvhs#_U~GwHYsGT*`H@m9gxjsoR}~Cg|+W~U-j0RF$reC3;#e@hboOo7;Q)P zZTr9n(nD6Ucz>4N2Mq)=! z){ozNw?{x=5hJe*g+qbrsy2Yy6sWBL(Oy%lES=H0y#q*nwyJ7eWkp4_fj$O{?VI2d znU&bDR^3?6nN2o+>XzS$!^M2<*a=rxx@uxL$qYF{>E;DJp=rR&*ypzAYmr0d$X zkH8lF-Jn#EX-G0*xy;<{sDH)|etra~Kf+n*2Gy^o&RxEAS~Xin$+iQv$fy6h$IY)1bMg#Og!()Qb^sR79@W8*gKrtlf+FXE227SQp>4&P+i0A!cETLo zbVX#>ZXUoV%ec%z6~-=c9^(K)xy_RUi^*I@88{-zDCyzU*HqUkU~uBdF5eT(Xkful zD|H;VZ{HTbiyA9x;|LJo7%~Td3|DqeoUkHMeB=Dl1(j&I(jj zvWlR7Xcr#*TN5Y3M46Z1!A5_)FHV3!kWvbCLQ=b9VH*v0bu)h`r@ zLRD5N!-oI|A{tx_N*I{|>f#X3*tcV)97`fGwS44)5QnEG2;Z&vP&j_lv+CQN@&nOvx-Fbk+59Xs^_)p0T}%wedV#y$WjIRo)MsdF4S zWUO2J-uKl{cIe1yuC_}zQR_L6E}S{0aVO)*XSjdrKnZ@%fB35kWdvJ6?bl2DlG!+DuFYUjuA2<`+4%{9yfZzd{OVInI#}c_LU6t@k2Y@y7#`Xu}(^} zqI1a9dY!B5)=Rb7i1n;^^ScUwg#BkFKSAiP$dZ)UI?>Fvv?z#(KoD#5-04H^=)R36 zXq3|uNd1; ztE7gy*DR}+v_|lsQN7YD001BWNkliRY|aDG@vB2>P3ohUU1lP+@a)CdlXhrIC!%$-VSf!%m=7h#Bl}u zlbsU{w$Bh#6vjcb$|J8C!oAQo1;B2N!)2ERq)fO;Jr66ZRfEpIQR7q7asmp?w?sh& z(4laMy=Scxq-nZwL*D`5BvLK=jB??*69P&&&%?*evh`WrNo&OdMzwP8k00JHbwIKL zM-OgMAO+?Dwu$dXtb)3zhD&GNo~_H=^(&WMRduzgAqT=@ew|7r#dfasNbJa18*pNb z$Y=rt_=8gkNZh>YMFm}kjGX399Ny;kZ2Q2d#u4SOe)7F)a{y>Lab&wOU&1|Q0Am@j zr~ps1G92S)JmiLsoazqmU9YC$IO$NoX*v%581M~f2DIbUQsc(oP_tAA5vM)YZ!u zT~p&V*R$_1QMn05uqM?KN9W!ZflSsSfsAWc8{GDdue*z9OsUv5ch)xYOfU_oW2V0& zfj)qusM4N(8lQKOQT2N%tuP`ZIs3lPt2PnkPx`7-Gs(Z-c=iw7zU?cGR_tp^gPBeP zuC{ymeW$wa0$T)?wr_Y{XV%oYpOmul)^)FIzf<3jkQ!i-a}C=Ngwp`*>@lebS5&&8 zqozvjlU69$DCUG$U_!7ipg|8GJ5vk|T9ceTaX@T_1xtQW^LO^te$j%rZ+Jrt3GC9W zMbGGZWPKS!?hkN^%_O7BdOmS`%Cc%>Xj4*W~!P8!9o#9`gO zzd~dy4;BMViGhnKhk=rn zJbDMQ)s-Kuf*w$ zFB;TX3lySv(}9hXLDbP|MZBXLPDuX~=D=ziCTg!hXA=0y1v^rcUEDKJZa_1tt9DTi zNklTpw$Sqnp%d#bS*b%$s%;)DqPmC*8cshoP-H=LfXb=#7c4{BjU7yaL`^81BBoMV zEvL!)teOI>z+gp%BBNwG$Rb093{w-gJxRL6N8bx5tn1p_HPJBM_x;0hhQ1YA3v?JP zc63q1+0W>+VK0!~={;bi=AN}kZ4LA|%zl-9fM@TV;lbo~09KJuIi5>>@QztKa#a#ulfQ zu^`g~E!B3rpY7&m(c;F>SnM{he%T${zsa&?C1~WO*MOa8jMd2cId0UX1*&}lNKg+< z=9g<}KhTP!M_)CLr#~%rfI9(zkToC^$^IAHLf>D!&23Re_9_Axv15NH>oxybt-j`F zl@CC-L$n0tOM=X;F_E&@A@f=zAU|QoL+Ty6d+Rc_P_Py%C9V||Jbl)W2ZsqF5t11X zxjub|yRGYAb7$4t(~n8Qy6_6%vXdyl+a8uuaG^>~lqfg1K86iMn>PoLbcnqi%9D!s8k0LvNoJn8xl8sm0t zen%PZ=0@9t#V<>-74e#Q-CLRoSfrZ*1V$Yv&YE99^SK2!dVEt5TIgy$zGCWh2l+M z1RKHGhW#aIMQt>}P;3hO72rtQBD6IC`6L?X1&m#SCVckPA=QCWuR3!4d;vt-R6sN5 zIS3wb_6!>{Q>+|VG%yFqI-fgrST+}xQ+ha(*(O*-mipL%%>wsR=YC3aOD!ojPwOIM z57M2+oT8=+;H74k472s6jK{EjUXBH2j4fuhjs-V(#AGod8gE{eAdpHW5{eSdx<(M461?9f*d(AD9jlSGT;-6X`mtF#3^%0y(B?^&fN{fx)x;|jk| zZ}>fJC2$&{t>dIo10~1FuhW?7T?7^*JJxQa5PfFk__@k5FwfK&t$g$E1o%f!TlgKtwOLa+9RoEAv5*zRDAWY{O z12Jg(FwQ+}K#x9y6gWG6aGUDM5-NOj=9m0#G4U#u38d#GVDIRGt#0$`7t}_@oa3~u zM!a!!rgiD%I(O?SAV5|aHB9;pA}+Ig>$|2Fee0I!kKxcuL7LrW8t}4!M0HJ#tLxg! zb*kyC{ej(Ly@wi1iNcZ5s;+T!ANZ0QqH_ii3}c;;4W)(>@hSCCt?Qz8G_=70l-RTo zM5vN&=YGg;)AoX~+p_v)1qMPuD)Y>o1D?5p%_3_@Hg&`D=e0Jpc6COSA|qxElqkF- zr~10Q({A(17u=lte?bbQWVh*+$eK5>o+J81zCZ{P!#tq&67d=oWXYZb@CbPFw-^ge zR^9-(g+&BVq-6y(Pv*OKf5g5fSZ#1~v+NKxq?82o>^0a88aYYy%k!rWD=@*CNbrk* z+Q6X`R3FTkb6xhw+IRm+wbv-iQje%nX=!m+>4$untaXd}D+1=V)+#FH`*MF*uUvEk zhmO~^38pHb*k`cYy7o19VApEzALjzI-q&Pr6AXv$N+x>!dq2=QZJ;{#1=_bGGhnfz zQmh05S=eC4hBhPseO=#MGH=Cl*~a#LU-nRr?zhN~NHPPriwf+kJ_d`o={@{pKUNrC zKf47d8K(}#CZb+A0nj$Ae^-T9L&UK88UxXyEUFUvDYdx_OGPP4WkG~wZZkrWIm*+G z89O6do9*^GezKF%=C@%)iI!JE-?Ap|rNAQ38=Cm)P`U*tzpD%_(SN`{LK#UUy0y(3 zZmKL;v=Pl7EMa6Ce?;k;qTq;X26QQzr7| zuN|nU1Wa(KJ9X+TL6_!cqxZ#NF^F(r+)TN3fNvFWIXVR5JXG=6WCqHMj1YlUkFORE z$m@!5;y?lh0gX7{^k%XiN-d&V5k2KIWMrjM+H_MOgSoCqqSnPL%6t{pktx6is$yu& z&NCbJvY?1F2Ol+=I51EcTOxp`ta6Dum}DM_u2)&@BMTQthkL`BwoGh#e?{4k_N>XQ zC)MWmiQfPn4eA>p0xIaG3n$$1!#gy_nV5WT4F(lETQ_%>S+sMK2INEBpb=9<)8yY0 z8>9WjHDeF(UD#+M>xg)msEj$l=Ir`8H4oF)tiL}%uUcx{GRKPj&u6&?**$?_s9*pX zfnn>fDRB=8>)aFwNdj!s=y`?(&=y$C+X%mBc_#MA!X;mK!|G?b%a_hcXoQUF_~{So8Fy}YQ+1ZK zh_POjJ^<$T2b8(Va~_vK$AMj|$_B^$Ch(L&Ye~aircWo}g>j+=jjRU&25YMjC+}Jx~fjHT6&IvMCf&Ib#Koy5>3D`w-w@cSPT4!Xm5|JlQ_m6`^ zJU8nJaEX1Utpjw*nCW0i^}zATkR_94K}(TIvmX;c+qLN}*Ld@Wd+6!k6tLqyXlDVV zCHQ=T3lVXo|-R2WB}!& zw|D7fVmdwptBm^18w#XQ!^pnCPX$O~dziC8*$2>*xg0orqB57PM?e%5W!n8PZU8@+ z53CL50AH6ZauE9h)S2JgqRb^p6nqu}J^+5iuFjo2kf=6?jGs3ing`Yk^D}DPJ#Ocw zrJAEeAni86Vqg^D8v)3vZRMJXB2inf>ubM+`u3FGA3WYX<}ZI>a#mX)iU3&mQ{y>KFvND+riy2pFx5>c6+wHuYFIZ!B~@af3ee5 zOc`&5hMJjoKQ{%0f(E#`4}Mv|kPP4Y4}PRf3H710c%ViRdKu1Z%yJ259AIVesA-}{ zLYqaPBhE?{txZn>4Pj1zKR}b7dqyoJ`cL}@3)CcWl87#vIiEahL&8NhbyCYk42ilf z`l=x^1mG1F{p?Y9>eya);Vi1M>5eSkKOe%$S15=sNbrG-3^mqz<;=G!HsjNJ!7fpR z5e-@FCeQtZY%R5{06ha+9xSpCeF;U#Kq!9#J-$?gKQvK!EQaNM{Lo0RnJIoOHd2NUZ}_4f@j=_@pBaHJa_t_7i>9X z>%PT{Q#CiK#*MX39cIvFz%Hs5vZ|95KZlN);f^2N;&yC&OF=>SQwHtbZ>XLdDSip;Mn7{bT zV&u>+L$u@|_;kBq(SIM;L@aE;ka~Ch+7)+T_bPX-0lfsX|5jUSWd(U|Q%5|izn<_=I&_|EskWi;-q!Cs{DmKXptTWD%_6lNLDYbTqZkRCWi}RdO*k&l1k4eod3uc| zlE|khdr9GL8S-Fzfk?UoZ+q5aU_i!z=vBk{Q;MjY0+pree^y^@fyEI0G0I=HtEug( zXf$(#A;H*$-h6@b6~?7qV^RhzS~d#fZB9X;n9;PG>`kxULtSNcl{w=)}S^}kc?tkn-;V7v9~s{@`4gnC9QvJ6b?4_?xah%zS?utLC`}ADtPQzux3R?rH(}r@Pg~zZ@4l|WJVZs z>THO%QgcTgn$c>q5&87_ZQ$gT&^m*L#a`@%Lz(L~H{MjnrFY*U>Mw=U4{!!(U<>#| z-H0NPnn&*@Cqf*73KcxZ@{?7RRSXA3oAVpJpq1aUA z?L;|xdt3G-6Rar8^t4C`l{y-N2Lg*V^y}*^=T$(EY=u`HX3R~Dp;n>`*lyNQ=Pm$E zv&%*c_Ek#(h$(AWsbGVYPp>uTy9gc$oYHzDaY+0gE;x6k;i9{6_OSM<0t?C(17x|U z8&dcq14BTFaXfZ#vobSAB`-+Xmp+o5Avo3hcdV8zGNo3(2SbJ@1aNd8Sgu|yP8s!Uf*tHHY&tY)Y$?G4fMRGV6EHZ~6`*m?LtoV$(K8be zacK7%1=ZLe+P~;MbncSJlX7viHcyPMGnqKo0#LPoFSbZazvN{`jDe zK#6m;U3&<)Am~C*Me6-*Jr=XE^7h`$YK0@KIAhT>re3@H710_W|NQSO6A1Wx>&O2! zZ37kdS1wa**D9#q6g6|Qqm28hqr2SjadTY##6|AXrBiO{v)@XDIpg&+fpE zRc^+@Pb-V=| z&OZJ~`4K1#9X+E3<7UpVHRq;Ii3s%dE0>hLz?p#)PsB)t;Ho|AtzvMTf7>LiF{Jpt zFh=~HKT)ul9{e;$re_*X42C)di{a)v3L1+Ia-M?uku0`&eEsG#0U?Y>w$Z#Os-mu8 zN{kMbM2=dUr&cmITq95yl}&^y>FGSEg<@zeb9ThUL$2XCc?w;r?2M<T&}D*}st?3C4r?$3l9D%2`M0Us!aRml90(w;_HjwbMAif|-2NV!)o0%)Yh z54!+ZK+%|t9nTzEj@V&Sz9u0!#2+eHjGmW+mcRv6PMkzQIT8O*QGN`=p+y&$Dp=*HMsfEd|7GL22Qnq-#=WJonwGU_l0da0JVTlf9~D^`DK zS?M4krj`a$8-%iaRe=z5ZViNl=(j1W@_o(fyL;*UaqSb{r#0#KE@#AuQ0hAN_6#2JT4lMe8o`UkyBbChf$veNIKO?;AGt7d)?)R zb5dMnj1#rt62n(=ueEm}M{^cF0_YhsYPyLW(G=W|Ut+&Pl2M{JX?71iVy_!EdWPGy@&)x5<^H93+-snlI{#A+`X<@Rw}1R+?%1I% zJ`m3y^DD*MeY2$%%C-S8Y3YEdjWXlD5xZp*b1N(d@&H;RC(L(ar{1p;iv8P{D+5oD zN$BQpzwoDOb&>3=1T1=rcC=RbCiXJ@NNGE?Z~F(XbJyOkYtMde@UV%lx>FbT+V}sn zSDdXJ z4nntd#0vzN2U#1J%4&CX|0W4^#Tj>h;3nl^*{$8qZ!YHtcE|@SV^qpAeo7guk28xM zGR+_In*|mveN8m-mg)d-3NM{KE}9**7dZCx!y=j|I;yBA<3wLW-469eoCu=S7<$#h z1o?j1_Xw253+_W%ly>L?UT|QBj-DotI!;XNxOVi=ET%>UnAlOk`60|`iSbRMLM6tS zgHKZWQc{evDIEce(Y%I;InE0-X0nFRIQk77txO!0SE>4)IwVjLfL|^`KK+RP^+=E3M zoA9##`$>XDfGh_%&&KmYb)r26HjcWvkjaksc`;b@)6&5$to4}5$orL{8qO-M1A2IM z?b%oRk=oNBFa+qs0Rec4F6yJl06-i?{#?J_pf&)vT5c(G0Zoo|3vChLrqAMBi?&5e z6pKXPB2!HnL4lvsmytk^tvdh*fspIhE=qigv0x3bPWUL(b@1@{M)jYjQck8#vCtawgJ zl!Hc27U-k31E4P`2b+yaBk&=mgWW<#f9U9`s^=oui1T^j^igG~$V98g-!)T^A(c!5 zbAyIWbd%>kF2@^6CFL9;^Hai=x4UmAKP>E_piGJLJayhD#WJAn#>VA8QX3z}zGU{( zk5xNe#*(W%Z(GS61IVc9#2y+}^tHS`u%NvjWnp++=)q)Pu%G*Ota4jdzhwQE{pUl= z8l#+AKiGuAE8)FP%3v>e2P&yN8?@L-vmSG6-~FEIc?0DdQ5&wszX4ir|M*Ycp}iYi75h{a z_)ve$R^g1MDf~e7RK!OkFn~&~f{F3^jStKm3kcgn;CAlfFS*J>rS=8^l_k&omd1mY zGH*TqCrPhHI~vm{Xg;XS8AkAp{-LKCi|rriI#6i=!UQwl{NXpHSjr3fH^EE*A9F_L z5IYPwq!iX^3e78p$w9Id;+_sqF#~Ilq`6fGPJv85W>(>)Kb8C5DagsW1NrcX*;UFh z5HH%lYqhbA@NI+N;A=L6HUo1x`~ELTh-&@vXQe?9;v|{Rbnpx@cc8+NjYr&$Gh*M4 z?)(qMFAv5icb6Y$7H?xEd^8^s4He_cf!}oNrf5Tm-9X*MVIZP& z1nWXUgb;l;B;n=Dvw{ev?xj6*Rt_izaFXZ2r({V3a^W%A z4>&IzG-LqzMZ<-YQs5ggey*>hsCHK_o>nx{uAk3yaelmt=C-Z%m|q|n zI}PtZYWiccZ=nBzb(_>y;rjJU`kT*-f>%=~`Y>52$_wZ-hqx436g7kg zCyByj>!8A!dZ{_*WQZFjYGnNf#k~^Mj^H4*ii{t%yxbFZpXTGL`RdUxQ9dMi#C=d3 z)NtXn-kUg`9w=JfV%WKD0Y$%pd{!~od-mzTp%dLbOa3RRJkoXo`Wm2c#Mrs+(#4Z* z$ND#{Wr&HEjI8iCtSNpcTueD+}FrGvIZ5n4|J0LuS@+NDNY$Q%K6h;&NF@{G7+Jpd> zz@q4={_Lr&RA!275-k%DD*~(m_z0pc{n0lCRuCuw$WktVV9~sXzU)@L^^aPEfIiwo zK;a!X?Ez&P-~7?H6zoF1mvw`>Z&27|-VufAH(-=N4q05l1X+2qf>2Ky2>sk~%96xQb=%icM zzoG0K_m4e7ftY@aZ~X9&1jyKP>?^JZqXFOsotIkTQ^$4*#6I@<-&4zujmw|c+IajI z{*60!V3VE|eb4@p{yQjbQA6*0Os+w+UuWwxW zV`Y!UoJ!hDng0^%`l!K05q8wXd)(%gFG}UrfP6MsczgSg`fpkg%~fd_j2@}7%GWOK zyWKUg*e)NwonCN9GK+0p@-CgvZGFwhzxU8-c>SyvWmG!ViEhCm1bq?59-cS~RAd!R z3C|o9=mkWtl~JS?##4@@Aa>+A-yR_67K$GSs*znfAA3-`!D4TTE_=ER}xiNc~~O8vfT18^BQL|xT8@V(zU(oPx`jPP@bVHY%$EcmY&U|6}Vh{5OV;C9?E)02bppwI=t2 zRpSG2qIViC6s|N}uzFd)&g5MC?+lsp^0q4vXj%`n6a|~2ENjSY0qDB-9waGuY%mTG zf>6|5<6MzJpf?{t5gVjzp%+b1tzrvo3KUOoc*WzZresPFxN8lTc~-qSHodFs+_|R! z2GM@zkZY=4lA|wTX9XVsizpdV^NgK9sDiyr_7Gq|c7=6;lXmUOdAEJTQaMtHyO^j} zqwXJCtN@j7(Gu56XId9@(3pxE$a1elQFfSH_~8ZLBwqU?yMbD7opW6E<{k3u|#5@@8K+DKN48lwdGwY zLR!DrglyaD)1{gBY}VcEo?l-+C@1>q#Dx+OIdWj5_82|kwyb_hfCF$L;Kikcf3xee z{aRV&=E`kAs_$M$a)bu(DeBG{`;_DyBHnI{0%t;QSb$G2zed$P55j`;EN zK~4jS)Y_W}i89`|nv^kz{>Zqq)=-7ydH^%l`8z-UQ+*B_1&9Q|(8^%Uqy=u-OW#(o zYuyZzf&h$=Z@=EJfTd@pr+*bXvr`?s%jBgV~f zeFxXOrO$p-HF4voKjfz0^P~VEcA8qelZSV>om-YENWo@XxltVVeCJO5n@w2yrDw^eEZ zXj=N*AB)DDp;(7iYnvo#%fUR*I*Q;3YOGQoC1~nv4*}sFCE_ zsJg@#|lw(>Am>+5B^ZCkf5}lJiJru4OZO4PyeQS|JA>7ySKe7X36}Azvf2N z&vGw+@BdOQ^QXW5pLD;>57|z@K5HmuMcG_=woprp?DyOUzMwf;{>FEGnElSWVb_);ly}_DyU1Ib9F!3AOvlzMFt9Z}slxwLb=n9Xv7b?Ck}>BA2M?)Kv$5 zXtr*LFb!jCeYEIS+PA2xN(PlkmAL(N-4wYqr`J^TjLj5if4R(IG|91JojywI&R3g{ z?ECbvkB5$)u81~@adGynwXIV&JLN%jk6we^)vFiXHK`}w;k~x`Ft_)HaJp07&Pacp6 zOxyyZ6j;oxk9=m&Qwq683Q#Q)nT~lnJE<$ieyw!_hfbm*%^gMk@8%6Y$)a|#j@2*GJ1kPnt*W+cBekMh=OH_sw$Nao;Ve^Y z*VK4T*M-7_Bg&qX17205U?EN;R5xf{OgZZTkbm>qWn~g^BneKiU)77307t=zNdOfY zV8veNe%W(DNtkm1DSYeGm_C01jY;&qRa2K&M74gBECbYJXD|Akn>_E6q7R~2hy$x^ zLv^jd+sUIl?S5(1k+0R()-Z7h0mVrRl_^Ek2GwQ;L!v4YnL%p5o9g%ps*tfZVWJuV zZ@?o|HYl&ultT3lP2H6-i`%W37ilZbXLkhNDF}87;>B@Sb%FcAP(R*bN>zRRB7u*QzGpQ|(y`Pr%9k*rG3vSEWS45|rGUpQlxEtR8q3XPseCD^@ z%D4W`?b}9{%l1bIpfVQhb%a|63>z;n1<16-dRQOn#>t1V!h4{8lffK5cD8CP$+j+f z^k29sb02rtuU>Y`Uj9qVj4G%X9Tnlo&7CLRdk&P)4mJzg=(Wq%zuB}BD&2jb_%+$y z*M9I{T;ugC3NACh1fRxDH45^IH^1uzdKv{5$t3RD^p4xK>c@`jf9fm$LAIs3w$5ET z2VM0!DgI*D?|uAV$ma0=k>h5&VPj^iL}dTY74F!Nqg~5AIqk_Cz)za2vj2dxElUCVYN| zzV|k6wc{V@STMQc*Z*ifQ5Zepo)(-3HhpR+3@VtIO@%Uv6eSa3#t_i+hF&i?3^+DK zdXSKoc#53D5UDj8 zImxVsF^IBU*)^LUG8~LFp~iXSegLqcRY~GUL}yYSjA^93Gu zJ@Xiff(c%#oBKy{9H0YDT@DTa;^IlEv-116Zc7x(T#v$XU@@-qN@_8Ef4-u%;DZ9( zEkKIMInAqiCaCf#>p|N^_0FtP3ZLWs($@C=oL)dDSvG4gP^tZipa=GxdvF4ZmQ^G& zk7IU&Y@xr7+8dyPt88JV>XD&~5q-xF;Ak<<*mleCP>bd3&XRpx6yhm8^hvfnNnIsQ z8$bakc-Fn26L{FSbA>3N*nPyRa3r&$yD2ICuJpRK=@vcbm`#^@7*Bv(I9S? z1&k@hmgeVVl&}+I_&2Y9S6#?KDJ^IV;(#6x7CxFa} zL))xP#-h)tUXBbs^Lg#cC5f%P_>cdGyKv^X8#-#L0OG25{?T1Heat=hwNSJ$H2fW;bchV^Y~A1G(z0|E^5*BhUPnTj9Z?u?0+EDP+2#Hv@Fp zgUm4uFbgOaLBs6+3BaaM5U2;B5yaiJ@_E$~Kk}L1(fTE;`1T8bCPqkF|L8B31Bv{U z%<9;w_qmZ{=ctDu!I1#;4J=l<2R`-dYESg?_x_Wzzd=nK+p_SHU(|WA^hbZJ1O<;l zNy8Ig{C5Jfn^wJ`pz{-7`rlpGZoO36fPTQrxBtQI+xos#pdbDGzZQiV&^vv>)2{!J zv0?%svI8}nfED+#^to@TwF_fTMj0OjRb;Zc%U=Gro}DqDecu;c{p3aNx&QVb6qtDU z)BmeL=I(9pxt$x9sy?|qSS-kPVuSeJb?<#&=VmfLMSyqR2r|yN92jj1i&IR z(6wWt+08LzzYIRpOLE-NM}n&zn-$;$!{8p0+!?ez`*? z1{q-vEJN%^OW6V_sOIeB6tWJWospfusFT5^E(nllAiw;q4A2WSyM;edoj9Mm6+KyWbjq8M3!J`PwMcqn14hY&nU*amup z*1@72>evQEATR;htsE#g36@bD?J1HMrAjE3LkVw%dGi0)K{`uE4udSfE^i|eCV&?i zQn0T1mVi3}83dzvrv8KK9V*Y*YaDht(M^`&w%Vo|>jjEpWM#GGpDFGEY_SlcmZm6cNi`82Jv>UH$49F$|)KHehKA{FHI&rUoI{Q>x z+R~z$e-w_-pFZjuE}e9Z*HN%c?W%1FV?ShTH`84J@aOCqH+`|_-iUKh6NRYD&@nUJ z%mtq=28(5ew4>*1sq+Hr@vza;-L`gi)Y*GG|*>zwCPVAEvAx^?>xz#QCTGj?bW>0EKke zm|5=Z$^D`do_LC-R9LV>D~}b0*q6q zNX8l}Hni1O|LOl$(2)Lph~=z$n_9>UH*?`L?)_K)+8sTxMZdfMiC+^K1n?kg0|STs zvh2mb5Oopd&E;?Yt=qS4g$byr-3?jMN&zE+A-(&JaNF0vE^!x~)0sYc<@XNThqHA0 z!cXgacW!!1Dw+rbO_}?If*8M7>E9IF%tJM-PHx%&yfsW7~Lb_Z{fyuIPtSQiX}H5P`#kVeVwWN-x*E3BEh$tzb#k&Lc9?WLhc zr=C?=d4tIqLD9l7=a7qEt%1*<@SL{sb>-uc;W#ko#UK9u*;DCvniw~`PMy0+ik|vJ zfFe=J)5rFzr9$IP=xMAUi;~7pL{gU+IYwlG0EU214iQmQeXWYbHe7|&Ns}6Z+!N-( zVwdjy6riBpMO~L}QY7P0vaDqa>bOj6z&Qgdh|Uh1r24Bvd)F)TVxLc69RZ8+BLu){ z;~&;r@iZoD%!5T}aMUpn#gr0Zh{ptmQd?lrXZLKMn_?k#PL(w^ZouHN`uFjJ+gor(2U;gBDadw_y-E}rWBRCntkyD%t%Aj}C$K5!^4(;*q0s`Uu3SE6)YDi2 zvqUheC~MlvF1mfNm^&0RbbN0jeSMZzCYdKsePTZX=#Zv|*+3=>K!m^$fe_V%YBBnD zIArFlswG+@r(2DuEz7P(<(}3W7#IW!OzE#VXv4MaU z0%weKu=AoE`}0FBIV!CwddS4LnGwluj?CE+SR>eVsD<}E{x4nsq2sjvS1kQI*Qut? z4IDnvojJDG?b!U5vJH9V)o>04TZH{WXo`9uXlFxCTN!FTm6)W?6##=! z%Qyi=gw(cgcvH?R&KzfCr@HR0Tesd)W#t?qbIbWk|2SAUC?Au>3K@%#MbcU7v$p|2 zCRD_kOOz!6$ciG_cwLMF*bZdBaIyhRQo3#hOmy^o&CeHW25^m-$I*jZMAglRY=k;F zWl>qTwQlI>83IZ*HC-fjw&tDhNr;4cQwb{pki3;qRvdaXwYVM_F$O68QajkCM?bf7 z{hRvyyobIbS}vJDf)&t!o11R9&fWUBQRD9sH4thjb&-I?K%=J4aKXc0cW=G$rxH;? zjd=b;Uv(?q`g@5$p{h%EnSPuPeDZ&mGATf6N0 zVgL}td-tVp%Lf`bbey~Q@qZ~1pB}viyFUGgE2~GFB*b)B8>oPO@ao^F$1ZC!sBNl| z{Fv#Ypi+y3II>#CN*xz=xGA5XO8c6>z6;L+S^Ay`@6c=!+Y1erO*9| zGNyr9W|ZgNoIHKl>60^hCY9$#0@*4R{a*~yEt^zbP4#NNJ{W{$Huo* zZwR&i(a-&^JG5`T2@Ux+S)65$eeU<&uC4F5Eh}GA57Eaz_j|6kOHV1FBHTn)_T-`M z%J$v&_^(K83koe+>h82ds;Y5sKKCs#EdZo2Z&oe+J2!Uf0}|ibvHnesFLliG9{Q?i z!$ieV5KE!rs7^R;fmnz!8*H+ViCCOiG>O z9ZQCA&wU4uaYIH;QDAWY&egIXX1_YRn{)T`F<86}_dMZd`_E?Qvm^e&ZG8Dh_L0Kq z2@6^{+@TT?S+WQoHEA@4u2qyS)brp>kjWsb2o(xS2nS$r3YB^5-bap$L;<|=%n0sWzHlmaI5N{)?t3yZPXAdVY6De| zMHEx+a@6$vX9X-~s1bUIDBBglia+FSSPftWT9cG;y%Pj=1ZM#GW+J6VJN3$-o^EVT zZ$uyU4zlP))JEYPQ47*|!ojXz z%Y(&iMv(g*F?N=+C>&lv5iYFTqD*9xzbdiDVgns1|K-7E-YO)q-9m+^aqKmMHW$x9 zc{`Ns0lhEgSeCe#?8v3}DB+#z8nr!vf+Y%Hpy1^9j-N}$l>m@sVM2hwXYbS;-rr0H z9Azm~`SBB^4|KY=GJk$Nu_=IOfE1YwY!J<`FP}fN*4lwT*&Yv(*82Zg!ZIHcJ4dnGJIvWTE@^|RdX(ppIUA(AfuS3UP zXqRENwTM*Qv*c@T)Yy4y9YQ@5bT}UnwMYhjc7fA5R*Uqu;#?N?IG(uDrp@oTxCyI1B?$p=eoD)>zyzAY6xEx$S3+t2G zII>+(Rh7x~Yd&fE-Q29q9QAmUW-ie)ZD0SUGL@?RzIk04KEPrkaPuL8#SmD6VL{6d zvZ(;p5Qs~*Mxt9#(4L&N=raOQ*DhajTi3p%tXmU7MdBCU6eM8LxAM|?;0m(e2IyzF zk>lnn_)D!O!4iNLuLC<*o9Z%(y;m-%g~*HrPYa|X0>s*-wwH|0-fhcWUDqC>L%v0S z!vmWIa(MsJ=l?{RU?`h?`;Sy6ZpNZdtBuCS70(MG(UN2GoX6c8Km0>?=Hx+T522w_ zgGhFoIohI@4b`GYqPogBK_e%?&VIFw-nU(^zC+xjpZz^$*$(Vp<*E?R(TZf^dH?_* z07*naRQc;1v|a8CiX+)7D909c@lde@MKn3HwGZhV+($K{)RWU{;qaafQjDEAbBX*i zGN34ss^ysi{@IK-*OPsysnb1ms_o`x-}gBMiq^gN1M54e;EB=a$4z;__3Ss)w_!4& zL;}btcT!`Au-?QO4-4oMXkhMnUTPMXeCD^6;UwsRZL6QW(Dn^#yW5w$#>Q(>Tjn}| z)qX?jMG4-v?p2jNutum^WL;5N=zhtCS%Qx)wE0#A(h z!CkAB(YIsocCHv1-k%1r*r9Xaqkps6sgz!ypMjrSusC7Hk`@jr4xKnp0w9#S>E#P@ zB={Z17HS94<(oIJE0ROBnP{}FTZ;$=ry#A(@bn`eB`0Eryf}3wG~y+bl+rnG2Pmd- zHf>>L7CVV9OLR|k#G;xj+i0a;`7DE}u~o^~;~WuX51Fr0VBw=*&gJi*2rMQKV8$=0 z-HIrN1{O^er)R%muHS$WuBxW9sD@`w?o&ft$zz9R@R^=ip*2PXO#LBe&VWhuL+c_E zX>}?E*HS1XYPUS^H80e;%byjZlpP7!LH4Knjk!eg3lEZ9=&NQuE>I-V&Yp(h~+_=&^YlsyV0 z+4PB0Fle=MwNjBYx~Zp;`gM~wBuU3QUu{#g6Se--+rfXR6}#a30^*GJ=|56IDh_TU z=>#yyGHY!|6#Fzt5;yQv18jd(SVaa`jXaB3%4@?{dQHN{l zL{nld(Dw`hF4`X%F^s;5^i#ANyC5i`Wqr7j3Jo>)=i+m1eT5NS8J@&H8nN4&Yiov`l%1N zK|?3FL;KeYd@v5B0*0YSAfi!I=R6^Y567AL=+TG%ZoLJx3Haay12hk>2nM~B8wAe7K>?}*#+5A_cAy~;yu7>sIFBema&%Iv6bnAJ7IU2 zLxqnpVdfH1{J3B0+qSKJMgB%+eMD=6`?mlF>#;)AU+UigIAnZxZ+=_f3lN)g-xu^9 z%s21jKJZxp{j^Y_wou|%6I8$a~{ z%@H)#YYpe!J1_l(Kn@}`0Do%h*be}j`bi7jiKDxe<)n^||F5m>;(GTVcFlw7C=!j zIFzPzmLLtbBcWD1Cm&4gvkGXjJuQHH^Sb;h9*TB5)CmHr=^+_f3PD?)GW#)=y1?jx z5{kb$ar#4U;E0K$jBi@;yzLi)mQeSrYm|*0Jz>84;Pt;%DTUQ;Td>6&##?^S^vX(JQ^d!zYSGW{HE*8pB&A;dWnX zRMP5DFi2#W8qS|coY&&)K`UU<8)CVvl~u}6F$QE60XA0amELVBN8xs#<-`13t6(uQ zfT9YAX5~}6@o_voK|Rz zH{1A+FS!T_FGm$FSkL@AH( zau>_&ixLND`{y#B(oKzo04wzDD728QHQ&A=v6so7DYj9ejZs3A_Sr77jfnY>O(5D0 zwTtXC!c3j$*$CYmK!`|=7$JzDSg%G4h?rmw*G14QFhpPu;AE2x159B90XK+-HQ(ZS z4by-)4+bSXt+4vG$*IOCyl_NsNuXfH#fTN>)x;y8Gf%9Mc<RE-jU!$A}AB))>Bxy4t2o1f6Rn? z4c=P2ij^=TaS;DPrUv(#ZpFqG8KG)z8liWj3{ib{G)xVbb zPB^Rj4jSdA&HI$r!{(JQ2&4u&bz;g|1B+e}e#oe4>S@UyzS($P;F-Wsr`qnS!K4@D z*;5CVAd+k@V}Z@VkL*9BUVDJCynOMLJ9p-&#B~TJ?A-K@+q>;OfoutN z)pm6~dJk~pr#+-KuyW~lmB~-&y&e#2rEyQPb+?olfk`uQ`onI_n@;BUhW)i z#fFyr)lUOh%-_RLdClU_Yv!=6rBfI-W=5KXh`=I6%AGs+a96HeaJ98vWjqyKZa6Ea z0;7Y`gg!$?2&1X&WB`3~K%wmfj)~C`5yIg8IJm0K2oaLo28(u(#aoPMJB||d3rIRA zhkrC0tvP>56v>YVhYk^7GpPB(<#5D>i?=&W-qzfFD8DaDL-l~4x=bS7&_bbK7*OtJ z8H?Tnb(meba^9UizF$s~4om+E^+X|qlhhZL0gH)}s5ih;S*@}L2C-{ ziG6h9@OIazo|);Z-2f+NtU2_FC4%fCmmT_J?+;19qD;|P0 zD=XI{WMKW@@qWs!c>Obg#SmOmy_ftFpFORp5G@Nkhy#S}BI}5l26f`S`V19iOSC;t zIZd+)T*w?@flI)dy`-}3K+@dM+(T{2O zJmu!z{{`2jdvAAi{}$Ck@oel*oN;QqGJ((dLVoRW-#DJo4%tULHZFB1kL?!72#YMX zT_M{H&{l7`>5EkZ%jYhfITG2Nu=efmP#ZdE#1u6lhvl+s(_8M+Spt{{g<0P~>>bWB z0UGLUyZ7iX=M!)aU?(6%%K+3*5gHOL);p}&J;36O1y6}4sXmK2DtOWQE5oSCzAw9` zwW|FY4bUR+aCrARsi0boTdHVnL5OD6)-uKjkT884KKP;Az4hHh5!=?j_1+EH=>#lR zR9UTUMTHwUWW0I|0tlf@5?}_nu)aBy1`HnW4(wSYx}!b22PX*a`2eCF0lse6IRXCr zKl!iJ{}4cMB&f)8hCr*Vs*>XBtouH%IbQqD_p}GtKMF?B3dREl{2uNFS}ZIEGIcgT zl~PKj?FM^j?YsY^tS8xNfDTzmYAT`DlHmj(h0N`gIge?rA!I~0HW8m`%PX+RkJpj7 zDKQu7?`XFHBW&ISU)Gqg7GVeQf>sWD0N?Jy+2gYLYWt#0V1=mG>Zv(;x*JwMOZA`B zB3g}d+D^iH)$$|Df0|$BDc_0RmjyE;>(`9+jqRkdfC@^m(m zWlY$!WQI9=4(wc`wkfEy*LLZl+C`eyqf?+ZBYO#+REpk9Ha_(ag5PGrQtp9ZBlKhF z{3j0YatC*>RuCzv|BY(zLy5$Q`q^&ETw1bhRm+cCP^*mdb-x8mT*iT^u2`m9gZUoBu0^FJw}iy z8q`C6Moot3N!PE6q9S@>pmW%MT%-WcU8(B zj=CtaQEg%3h?R95v-w93ESxQj1JADLS(J%sZ?>|d&vm!oALZNZ(zyUukk2QI3MeMJ z%D5p?gfrHqM}Ijf=T6e7{e(4IZ@ih%;o`NEq4I?cZ3Ia283&sRb4H-T5wioVhGq?k zqn;UevzJ7dsh>clHE~|=Ffx_TEOK3_MkB_~b$hqJpHN_H9_f*B_cZFe`WK^IM5w+|M{;PetTi%2QL9i>7b>@9$*T9mNIl5Bh%0h1D$ z%%ap(d@%cr9MS6Fj$8d*r5tRiRs^>Q4pGm9BV>KqtbWfZmtmG#zqfK@Uv4am_El_4 zgIZoDXwmxQXQ;A8Z_R_UU{{R>#;{sRfNxQu=y`?cf3QRVkhPt=E8EzA$aptu!hB^K zaYR!Jx&=W1gE)}{1J9n=uiDQGr;n;W(AuMTGm=nygM*mbl99#d$rjbEQ$?J$=(AJre5jpaja>xTz0_#)zm0 z^gn8=%&wbp)H(~`-P760lF_+tIKg>;-@rb}IO0B1k8g0|Q z%GeHKVyKT}rE0YhE$Y>GxOxGSEheKtZ59+XsH&GQo^+Sao$}6ai+TwoutD8s5V&bA zXw#Ov8V-oqme@U4$Z4g0$LZsH)Q2@;jL7#l8Zv8;ewX!A?spSsEzukuf?oK+vjQlp zZ}a|!XqP_ADElw4=b1?rl?wWz2Flu{ZVwSPs|_{ahn*Tce3HOEZF({@5bD9>H7bEK zr#ec6fdEik^DH&r(OM-aN_M{ApfSpzAE%dX(@n80E;pP`vb$O>&9}6#=)DP$C78nf zp&B}M?h^{M;^a$Y2PIvAW}!mjHUJ>@BQ<$yx6sn8mLz1)*>Br6yzZ`EI-8@$XZKnu zi=uJ8bxRpJlv~*=R%`i~*7~~lf1n{FsEQ8Fn0vp_(L``w7;UHXZrjnWe*5S zD7%`dlN(@EkRUd%K7bY9UwSsCZ#1el0j^qsw%}_T{nKm+^~0QdP_D;Kdq8L26|bBw z-y!s-EI5f;QESf{rNl{qQ?0(5k{aeXILN074iJzSJ${}V-jlJsdgZ)p3IW*Ir|@=x zy*c9^+IEa{YnFY_ojAJF*WacY#oTZtUTXPMAUi^o6O5>z<7(x0cdpY$ z#0UoUGa`P_6s}*nm>ejj94mG*QEon;aUj|`Pg$^L^%NYsM2Vpng*uD;<;pvMDT?AS zs;Z_otf%@m;XLJmQ2b2ocFx=RY1Pq{e5oseT zM}!q;$9k;Ud|QC9gkgyRfd_)&c`{VROtj8th?5{fh_T64$`b$l9A4;HaG*bF&ygMCKP z_kn>h{zJzr5J=Dg8wZt`U=g3gp~TsO-hBS-F=cAC?;|RACi@nHEC2mT`9TO_ z43bR7T;G*+$`#w7s8R9MKeRAl$0=Gm!>zKiDWW=~QYeW=&<=@r+tdp|d6=EJUM zzu^J{0EWQCu&k7c_1Nb;jgJzL+Rkq9u*q)hl>3z7LD+=(p}vv~RwJ!SP90Q6<@}kW z%7{qJW5sh)w@mw{mUj5s+Mj7iCc7KR{-B`AJ1GohkJ0`E5!R6uzZ7QmKOFDC71Y<$Cf zmH~@C`))CFpnHXYA{kOL&h%;o{6bZxR*`aw+PdzlF(kN7YZmMQ!4z6n0GRRhu&D%_ zXy37O<5JB9YeaR9VTpKlLxzIsZ9>U&KR&5^Ce%jXGf4az@iU^|;MDMPZ&oL8U(kC}Fz}@7p9{tIVqdV6pgYD|Ihn z_kRo)+v_6!kMh0@SX30cs>UMAjW-jpXw<}8NlzpbwMmsFLlbGDYk*1$&54#lxqup{ zjar5RNSy$xn$ShLZtU!~cM=i<iEXD?ydp0FY#4nitYSj@C6(u4{ed5)t7bW-391&RzihwpAWqSRz z7c6ER+iaasJ_;EOe>haaT%Z6Myp=pyOfsJOP-HIKYh?W)gOoP{8aS973ij~;Bz^*5 z(dSv2C!*;%z0{m=urp7{*W;9h!}_+@q902@=#UYUMNgucJ!fFaA&bCbyx&^gyQRQl z#u>7?3bjzN6CuD{QRR9MAdoRifhr079Nn$@>fn6GG@Xus#r%DzmZA8Giq={(0L6CT z!vl+c&y)abG3Zo=FF0@Bc^2in1}2C#o!9^Kr?N_cHugFUf&hv{EAyoV;d#o{sOITj z$>@cB6Vs?-5FNGDF|o8})dekB@-;VZ+Jib@c5QjrT{v@C!5gxByEZSAFiaXaN*(@C zk1OXEMa}xzZrqf6-TBi;B+^04ALYbUcb5h9L9C7MA2an{*MA_O<$ZTx_ZkyTi@>;< z7jF-sidR>=F%uU_WCO<&;S|+Q1ze?;90nA_4~@RrqWwH!`eOB@+q3mut!?I|XRm>- zd!NA)TBDSMj0}!3-wXR=vT=Z(KtEL=S_;Yb*a0kB%`9gSj(@Y!G)GQzqbDs;z+&gdw~}YIRxlW( zW}RJR#fFZVq2LDRlrN+!VS=*rYkMMO<)b~D&xm<@1wiQ1wU7K2z#||*B@oRpPpsE) z5LQBcl#D22M1MzY)P-}$Jasdr^co{01=?i$=|y?$;5N5o;~S!bC#_#P02Y-ktE_a> z7Ch~SkC~-)HF)F{`6%zb@>f!IRfZF>7p;4vL<0(;c$#?HFo6|n(pCG}?A*ztJKd?H zyTr1xG8ChB2D@N`o>EiIte5tS(*0sJubBg;M2jl|HKWGQb)zRPRQs5no8LCQgvgf2 zC-E7{_Z7=oQZJo?fvZAWW4H-4v_3k@F^|*(2uM>kW^J=djQ_=(X_Y&LUz^eEu_GR0P z3qF3|-5r4pSj14PsJwuBmGwpx1r<5!YYkQlBDw(^l1=981Eh~ZcB)P_FpWrES6JHL zqB_}fqxcaJ>wsz^@q|lfqsHRNshYk$rZGjE#GEz`=o&==Imj~+@MPh~$DkdX+00-H zCl%SO>*D$h7$sFjXpxFEslj^;5+Zl9oD+O^=j^Ur&7V)+&?@Jk16rK_9s>mSk;|r_ z9ES{wpEcpO9%>fNBN|>NTNgVJ9n7d$jX-%YmVk$7Bm(%)IPhMWhiJa_0ri=N)-Zj% z#{5BtGeC_LnYKfF)=Pdp(p)XNi#q`)rJgNG%y=1XDf~6w5Ty$hOrph5FRh3OmZ*c$>EG(x^~@np6|OZfWR zz27npP6~Q*aoQ5^5BDA%rjBI{Z)5y&fF-^{3}m#%5@2IdfF$dvasbPCh3vUG^nOQr zFxMJbOvNCgtedCF7Dcy9WfH^vz-+0kkyJn61CgFR+m~yd_a9U*x;(w`ph=Ulg8Ims z3AN60g@R2kIQ3DZPalpTJ=bV^Aa+8?Y~;Wq4k7eMGJLeIpvA(@O>dhTc5s5D&)B0_ z-8B?$D68zzotxh=aOLmC+M}dQhfpSgoq;ugx*`-=+CR|l;M(PjIu~Jn0O-l05yVs- zYM;TXal|&SdGDV!HtJnh(#Eyrs0LR*J=3)NINLjQR#u1cQaha{Qy9+DT}^3{_7Rh5 z`OvkeJAQDhdLZ7UEr_x_+RgrpOkLH?vMKc%3&gpey$88*(-!OZn^wLcV5T$J2R1_h zn)@NpF>u%x{IHY@Vwd8J;0FO{u{#9mU|n%OA`H{5SAPZ80ELLG zAWlPj7kcgiu&4!8O}VFTQi@~v$WCH@-m~{WH*?YF1Yl|TK&?0{CA`N#k-fiU_&st( zSkv4m;zHC!LV4{39eD3L_ttZN>@IjQvQT$v-jJ0DAuhy=3^&1nDf2!lQ5=GC0AgO) zhKpy8DR6+_#yTgsB*r-VFwj!H5L2-e7+HeELCo7!t7i@61hCa6&U#eAqxH*wWV@^bue7E_sT5T3|MqJFaSFU0$8*uHWS65 zFn=t@--(gH(AIVCrb80SiJduV|FATh8Ju&wLdRZ3u2YGRcl4U&?jZiIa82&rn(e~b zC!&ZL0nZIcxOo1!j1&%eIM9;5Wxi)yssfn%-c}4vps(d=Y{?b!y$4Hx@M6;!e}8a5 zDnuK@u~84Rib{bis7mb>3E~s(VI9W$*$ChI5-8gPE0H=;bJ<)=Y(T8csTRWUoH)bLP z%6Qk-sTn+UJe(L&zw&_gPJ%aW9h7;HQ^JKauoBs!wyt?cGuHkOXMtk`t}>L($dQi# zSRQnmUCi3CgnpXox0oG^vUjV!Zw?nUw+S0#LNdQni{sQ0&z{UUD6ftKh>u~A(NeS9O`-J8y$2!cX-)|O- zDhTKS_&ED$bwRC>1Z{#l>F+ZhOFeH@wHnEf96wh;7J&{Lf+sAVgs#^js{%ZRUVSH-9F0}GK&=z0yR*D|9|%014^&!y3)Lr6LQWu6>`o52m&NX zF^H5zQo)ie$w9W;?jBE1yWO*9)~ud2)9&u&9%r{L*_M?lQ6j}4Mg$@dIp>^nD&$-> z>)Yqv7yeN7R{@l131ve>_``em-Fwd2=j^i&>=r1G^!iEpRTarlm5Y-|*kUN@2!N2( z%%7CWzW?TdMT>1%QtSV1t*SgR4b?ZQZTK1b02%XvkkO7!??(bM0pihLUsU2V=o;x@ z)h*@^4jM62_sd>`-4*qM`^1N>c#H}&tH8ng@LkYiM|773*8l(@07*naR8M(I)%31C z2a6%_!5e?;wy%HJl5ZK|l_iCIzjH&qz|E0L48D_nO7cBm-DDy-_W8;C@_*~akCa3xEpy#^4ReD>&vs`|9B^CK z{5+-pU5NEd>{ffZzaXl2&`HmqJuHxZ?Q)%{=ea4U6eH_hzuKv8WVI)B^V;F7@X~ zLgRerJ5tFlAA&=GVudKMx5TlJR5pY2&sjlCY-sOL!*?RuLH3Hw8V=yrjq4^U-{6$l zrQbmn)LRIvc<~Gc0EJUga~jNy9gzee_qtg!0ZjOQIp1OiQ+HGl&S(tQ5ydx*6TJb- zzKb3d5A056IKAcdm*^c?<`|S58NXmyqhK>50ifQMJfJ7PlTSVaYh16t!~QZkbSTyA zkuayod~XiW?)Q#m!|PoYjphT#i-rpQCNm)UsKH{mUueO|u#>zYThBdp?KxBdEb5Rv zyL%Zy6ZRQNaED7z3%$e z3*IgzC_~XrWRC zt~^-G0kZAAakgKy(Be|pXV5q|<&j@=-Fgm@zz%(XP$9W4=ARM3BH|IAMF4A=eUDUu z5U&7aB2aZ`&w2xxA(5G^D2DqhDRI3AjB|rWJ>+g&y(Ajsxzh&~{2FKpU?~kyVIYi} z^rQq-cC3F-gU6-Dt0a!ie6=7w1my+&V6ll1nf|*Pb*!YWz>Q++T z958f>ltTdwh~8muspgV+ymaA&<`~|(Z8HM{I0=F^oO1y1z}jhgzKp9t+z0>5I$FPC z9QG48@F#pV$>uOvK6jG&-oT<()r;Vm-!#=>lC1Rm(XR-2f-VhM-m>ydv2sLq)wSCg zu7|>~AN^N%vF?QL(M`-CP9!|+KJU7+vT8Sa%9EN`xpC#I?#RAP0`0_oC{NSt%sfg& z@Tyw1RpJscpsN?pYoyBMx>KU%@_U=5jo6k||HJ-?5`2*jNc1fGvj|&^WKq9ilQatx zp(K(-1?S%KR2%tR;WwidUq-9I}F` zYibc#G`<`5uh+nFu0!XZ?#8vN?$F+~qG9L!DG0><;=y7_nKzlXegGB=4om(eUl@T! zjJ5Ty02tf4n>VgWfl3tAYse^j09jHh8Vr>T14?nA9RZ*a5I|RCj76Kyq73mKt2W{| zi$xoy_XH$ON~3u1yWL9Q&C1^6Lwu{m$mazb)svOs2B%^hX`q`+Eqy`D~6Q7Nfr z0&}RgG=W!Cw-!AEuwfwihN!v77+>%gi)&*JRe4#Jq~)0*X8k-l0C00GO;M4u$Mmc~^SgZhq%y<` zmJ)1%=6qzquT6j!f+dncR4nKN!e(&J&z#(+%3@NHPeEj4F8ujx={n?#M3SG^M6~j8 z1dEwfzJ)qKL#}@@p6K@GUdluT85D!87j_r{`FEr#hfst#rVmgv*5IH{B zP%t$+s<^~@_k1-la%I6uCBPSw%Qmq4l)HQ9ru83*=2@+5A%=h+kYq(9a=;mszSOah z(?;E{%9T~th_XQz)5KT8e4qTsG8b4>&q!4(*RksWsVoAZ$e@XKTT~>+rZF1D#r9qP zI6!?NpgwtcyE19MZOlKz+}F@DuvpO1%ei*~;0VDXh8QuR_MLl2669R>*;D%!ghMR} z6iko4y`S*S>#1*{r=`l3l~yPVoLYbcu#8p$nRpGju2d$N0Ec}A^;eF>gF^P0=8#oX z$vGrPRiv_hnU$#2d?zl)f3vC~0VL+HT83MTxcutJtrQK5>K(!|MnjEvU^Zg$m#F-*8mn}QPSz~9E;@> zJ&C@>@V+GYG@uyzjdOiWNEqdL9-50+FK{yB@vpi5L#Jp=2Ve~#1g#F*7pkHriEkoE zv0aI6E$1A2(s%H9H?Vf5z{{>pi;W)V`>r#uLIPUM2W;KR4IT4{>(XO@JFs)LJFsh| zlBZ$cTcB*fHVEV3BcQ7?6AhXi!ZZZOfxaKxT}yZco5#Ncr1-wh-3Ge7+Zj5)QLP;f z84BSxE(UsTnX0Zs$IMf;6954CGLaEu=-ew<DWk%Dw<17?s0Th-i96 z#j+E#pZvNginK4BIJ{j7s3dP~Tnp8=jvBoIcwzmhl#nQ9y_nz0{ZUb*9~JQ-1L#)8 zRKhTTMQ2l zV@zqo`2Av3Mq^XetEx3}^3$&F%we}>?b~8;L|OnDXEU?1nC@MS!6Iu3XdO5GQxZxd zY4P?;f8wrQId9-qXD5+ROC(E71-`QDqb>{O4d(hL5*O6$ICQeW7D!l$o$rFOU_dm`GTXKr@lt9y@p}TwUS^;Z}-oz0MwU+0DA(x`0RMPDEWmY0GfkJSbe5NH45_89rPTgNpxOza3 zz~PN6T6?I4tOuFHaE+|L1qwz%ikBjHWic0EORhv*wG4UKJZl-0*tG6eNkb)$nN>JV zW}R`b;rV4g={P&DE50wMI}+{ilr_X!vy5HtaIJ=UihD?y<^+QT_NYK|aaB!J{8mpp7sI!6|dw3@CV8991gf zd4LR#M?42xx?}yj5}XQWR+c_GGkzYOW~P?OKazwZ5N3`d;{ZswrOt4oGQxe~gXrC2 zl+5m}AE+lXh{?s*832CMJ3no|;-C_+*mvk8^{GL>C#kD7_a7O2Kj46|1Bki+{@s*F-&gHkQMlhmB|aF{buiRjKEkQDG!rx_IG~=15+u zJMC`YqB3r@@??dZkulRA`I5VSzE_)$G>*y(#MUO{FHz( zpL_Q7K`-tT>riCcGZ+BlXMRTee9Z?x)OkU7+ zD&AROzUI(+=2 z>XjjrgkhXC=X35#-5F7TMof6zivXFFI@wS_B_Jqm^vqC%pRCGeIJ~(6@fL%{h?8e# z3K4;lGO6cbD5)GFjUO_70`!5d>M1H&U=e^)R<7rL^V$`!65BW=is&Z(=4HfvRvyQ} zKEmm;4*`pOK7*;DJcZs?Tg*5cnya!{7+ADxRVB2nN`D~hs-6l3tVVqe0VLl;b%SI{ zzoAp4HfUfmp5OKh0gH*fO(mV616mxjwCIoN*sY(dJ9AVb1KeNeuULPCUs#G>vsROh|0N(kcm z51Xp_c=U|z+O)u3ID6cDN}`uu0LBON1jik_7=;x7w{!h_@eD?Z#2M{903Q5D01xc( zp8ZFusz?tmv`hSFB>kW9pzwtNtq~KSP%@J~$}`9J>b^oUEe4Bef0If~W_)fg8Y)!N z*6q8gZ<8t^;vayzBv=V79%doVe)4w&1fhptxp>ZOZ(VerGSe&`0L5JU zRKnTppD_jc4V^4u8uk+4YROxFr{sT{&K$2sGEoP>Lje__xejXP$pbNf&9aML=qbV4 zNi!8pd=Q~P)`~a^rCX9e#FU&XD#j?kUa32)_7|#-N=*3iNmTJB%z8nIlpX8d_pB$o z_JS*m3AP*WBLO{l)GRl6ok=t5#^*K zzCytw1(3c&Cc4VXR!aUJ+G{=5aq!rZ%3=NEK10bg@BHV8o&@?9D;7ZBh^AtHxoapJ}O^1 zl)?A?ixI^m0!9gAklegb7#Un##W34qi2gcUC$_B`kNjY*2_UKR6IfomYI76`BGr@S6B+<9LC(IO3mA3l7}zhkQ=&l2 z+en2bv6nL`r@1~nGl(ki0zOtR%S;}rhc#Cfq*-9mlt71#pXVmdd|tMgY8e4E!@;lA zop!soF45nGBu?^J1)v*jU3IGtqG_U#d3fIjRim+Qyr+G~o~q&`-$SAlFiIdheB7h@ z&XY%Xsb5aLb?1($as*g{W(VyXO024RckjAxeTGZy0{?LIz!poO`Z>fBW+C{e&o>ga z;cOPWPTl&sq2uPN`T{ULab%~yBT#u$mZPXxHX8s;)rZ-A2X?JCp&t2Bt6n9E@#!j5 zQ`;yFM5q8!CFAF)Xt6h=zVGBGao-O;`E}QOz-V{*!Wp-1-CG(rMWS!R@}C-WNJ_Bb z$Es`A=0H-qjfTCCm^fee2gRI^JQ4j!g^Pslz)(KP83=NsaI8GN%X7LZ)>EnAWnHyL?`L?xxKEYl^_v`OpmDkxXx;AY)Yp&wa{To#z3FkEONzt|~ zlC}fmGSIJB_5OFBr?r#go1F+bX zQGD?4$#}NcfN>2KRW%9-ZG=LZfFsT!3|nQ>;>n$b5de?|0(F;kvVHDkqsZ!0($Kl4)>{EP!c)*HEHC`!=d1`eC1j38@>K}Jd$ zndyAl+$_VIqM%0JC`~&^fWAU@a2%W$IppChTeWeWx(-m5o~kZXC$jATvOBjB4k&R| zRW4(TOtx00Vb^Mx3Xbq%-8&U8$uCU{PR}c~E|y6jg1#mtKt$na3A9X&t}?0~vR>>vD&t%))VWx(F&$_W^4$g& z8*CI!X}O$qWvjNDF=v%$59|u~u*Se*^6g3RM^(RdhwhrANM`lQ<#RUY6QCFg>tq7L z_&)PPySRSY_@$@!jD23d2q_T)H&JCwo}&Vm?qmCs>>fq!n0vTh6Nu?OV2qnS|EsP` z_kr%hx#RBO&XuC9VT*QeTBKQ;>TCBEL3-gO!& zaPHIrw|@C6S_^vJlHz0}dr4+7LIVH5$Oy(e9NE9o9oV%>0WpDj$L<3}S4F8CzY5a{ zDmv9Wz&(o4vfas{lFExF&TE3gt23Cf4B1dD-dAw~I`O8A77-G!{fA9)J^GB$^}|L& z@FWa}*A`Vviaj5Ej*^chWvXnkpP&-&-n=C0H*FNangNb3DD(PxFC!+Nc=108q(i-C zd&q;eFW>s;i`b&Ea7~@7yeb!w% zf84EK_EY&86WhuExllvLO@B@*z3Z3#*pli|Z(~#R(n7$ZX@&G2I8M}EfbzjzYux2a zX9}XPHg&?Y{`~=1Z1$4BV2jH(#a#Wjn5pmhRFo;!2MojSVHK}`^SwX{NJoQ(M9 zRj(U`*MqElRYu>bZC9V^L8ao##WPwrg1_q4?OdzYog@*C5R`$L41j76wyEvi=)WhyA}?f3m0cx)(mX#_d0*R?r4udQRPT!e(KF@s^W0Q z33L%p>D0Ba>=+fXq7t(o%ud5DJpA zAt3BOWRgJet}TnC@N2eIUuPOY8^DdgC*AI_g7|5a1&biSQPEZ&2@HxtMT~5B9a` zvJ;t&AA`)awf9hwA5K*K{8$TmO;Ov$KWtm~w)KyO9>s7C2^%62rTPZfse6C*c;32o zLwoVkh0|h81!hFJ@?176%iblb_$0cg&-;oLKJoKZE9r%#>K!G%EGS8fgL%-?XV7@H z)|@`J+ihC?hSr(0Wvkh=&CkES@u(R2Fa(RB>H5zl{@_^~ctjwlyLxlkAHYudEx4R?6Y8Xt3n(K$^;xP^g5=*$RvQFX05chnu;x6#LFO?`d~4E)E9{+Wz- zTW~uM-ty6|fWRW#kN_0H6EZjiX%>9PV9|%!Iz@mr1veh z=$nC}3e}WsCqV+4C1@GvPaSbn=Kh+3=xuA?af3$AbgkNSmh?A2^wq3c{6o>0LeD}L zSWIOoeOMJmSKcT$11u&1MWCH(83P4F5er67p%lJwx z$Oj?-bOa7mY4%EcDYKW$;P}~XfGw^i_@?%b@)rOAAOJ~3K~yAWN&-!)WjG4%0mWIP zwlUN3j+FOexp8~CQE$uT3#ufLI0%6j{|-1N00a=@=maR$1L0?4di6FOfKh30X@3b+ ziavB(dm9H9=+qkBp{hBRY*SRNtZpk%#d)FXf#RE7YJ!&6^4%YwiBulh3u6$BT2%p6 z+twO;!aP%|AdGX#tTYsI9m;%rAPrrrth_>r5i-Mi*oc9(Q(cdKqjb)&XJq*g z>|Eu_%PZZOX`d9JfYy2P$aX194juil_VngeZwSE6nEy4Mj}PDbN7*<&lVl%&5YaO1 z1a_MqT@s_c2aR*nAN`6LB?#r*Rw9^Wx+oFyEoKrVXiuiWVq`_zNTV0G=3BInMZ zKH?7SSm~}vg|c4BJ6as*m7-d{eZ%|i;yD0PJSWrux%E|Y#-Z$uob-eeLi8z~IK0Cs z;i-gBb|NAQc%x^NudZg*UA8rTpl9C^TC1b`H{19mPc;^s!;7?3wQA=ce(HBsrNu5R zed`-;-_8#mVpJ1men#})ZEN4M-s-!E-o-5lRM!A}H8t(U*61~0oRR{J8wp9MNNJVt zlX7;2l*qB|sH&3uE-|=4n5pzGg^&0B7u6sx7xAC*g2m6!$AOo}| zz+%^4gWcmV{3of>QZ+kw`iNV<{ADHk!rG?nP^d0Br-~keFKs$>bL*G9to~DD;}`(X zrC*RQa?AdE-`nW_A;d+YB`8Xido2SJ&Kx3S0VCif<4S)3 zS+d}~3`mw6EwQ*n8UFyf$nIFhCa7>VQc=ujq#N0wresyDj4^@z-CH-^)oXR?6S1C< zJU=-y6zapQzpKH=WR)1|Mdb_GYciTRBvi==1gI`Ti_k4zpz=3D4Dr64YY1ZXP z0K#YJB7KVxQ2IKXkEV>)O!bdyApw&CF{oS6jc;--UI{gP4`2cyOyWRJC!>N^UfEi} z-BbnHLZw!1^Z9pEGG&cw9FFMj?c3_3U=JYL6NW$2(@Mo%35tfh+Uq4nCVpeA)lyxj z`fe4}l&K=mtrKVx7>c@mANuGbs-_3_d^TX5>?{EpP9_F*=l#0GPo^=TWYsYn8^HPQ z-gl(CaE1Zer&Nswz@0yJP&DiaX9SHOa(AuJioM00J9xb&d5YCZA(e$w}>vguqPzi=LiIf`(a!%;qDZ16ZqX zxFaBj?Ia1q96>VwTUY;FZ381GJt;~wy@bpcZPTHs6%$l%P6Dl62?B1?oMgVrhaBMXq+-JW1uRTKHXe zhXhtj!wMc*y?HCd; zA;E??jz-PYi!Fk`0cdvaK1fv}hM_ao1a^)k=Hi5@fmD{d#Lg8Hpq+d{DD8CO&0ebJ4Z_99CFkdC*7sGGfDsljRZ4Aah8fWa>RuBYCqb) zeTCb#Dzm$G$&VD!PM!B9&7P!>5jp}?55OZ% zve%$-qBw}gclWN8Qn#&nTLFDiOd;B2A*1I9s7J;%5oonU&;|fQ5QaENn+`o(849D< znPs)l`V&1+RAK0hFMi{n%4eZATmWcu`NbWkqIKBfH$?i#jYN3>Z^5nPCh{a z9n}PsOt6XTWdB=FW5RKI;1BJUiYHFGvWlwv4OdcL;jUdetLrbMs?~JBZcZ;${}fmP zu#1Y+*Fj?7?1{aSBR5J@fnZVhZ@n}G(9m;G$c4rP1sM>>c_G=LA?R6^#Y}oqx`Gh_ z#rg(!*Y}5-3T}mhL;6$*8mn8ib<8Y9;gJB$swXl1Dc>62J6KHBZsSGMatE4Gej4eo z5?Hj^aPfK-4i?ju1@-I_%4xjL-#FwB=Zdm@R+q-Rv=$P~s z0<=i1KvADD|0}9|(9Qt0a>S(hu0xl8ZvT!I`h^dTs}m+}5-ND?e0t+YPJTl3MX5pp zlGOu9zj(@EG!?8SgMG8X!6pU}i4E!AcevInC}4(XEsI@Tsvx;@k0EaEv%l{;bnYiW zvgl`jA0k&lpwE*d~laAW^_)?%V#MzziUrBp`u)bf%IqLn5)N zioXYK0LOM6ducu=RWXugtSfY4fGE!bd&cL+70c}KKIMaRQuNFguy`P1>h`^XY{Jq0RbW2b#m6o2Lyo;e^PEY3bN@*Ip4>Y4dh9$EVfxdl!UJSQAtq^(99R-kCmh?x!0IjE@6 zoG%$}8nAH;e)ox@SXQn;Qc7lb@4D;PsOnfXB31dx0SKcYueo3mrN{CrFEkRWmqGb0 z5BN-5BK=8V(bM%f^hllGxOT-IJG{;H=sirq{N~kfxIP2NS+#K8yUL7Cn)RaV+;gyc zFOXMeZV{5~89gxhZv zEC$PzBa?&^D=AUN4Rtnz7ch=w+NcTh@CtpgxYV_7+ff0TWj2e|-^0W)^@67I zWI-O=*0G?U%nGCzO;MKFH7Fabo;#`H0sQXjTBwKu&JOYaT`AIV0ucLZbE2=a? zfg}f@L&7|n7nj572j#UOqpz%@lwj)>tPnu5cFYVFr8CTP%gV0W9t^=G znlE}SrmNgT?osO=&Z9E(P@avd%UV>o>gb>#oj-F()VJn>#Xt)bO{%h5*;dvQ2Mt)H z%5&=I9__Ip>Jz)a%&;~5OH5B>uM^Cnbg5Aom(RJ2XOFvb5*ytIib6{zgB~tXgYQ`1 zW%B2v0*m>;W<(u}5<3OC0JkXM#jbb%v2N<4Uy_nE zqZR-iN*q;IyLC%{ED9t75BMBW(r@2#U3v}C+(ZKIySHu#a8S8}B28}=LL>CfeelNL z3Q+MqA?Zc6hkiHqvMB`@yTK!8XnzAJsa~#L^nI}qNcz#k4xJP`&#-O)6kw0)0*a*A z_eTBn-0iOWg6GyfSn6l49)g~lhVunbu z?D)uupHL-l%j(zNxl@N-eLW&`iNHGANKFN+88k|-dK^B9#9W`j<5d+ys-G%oGDw9w zssvt58#m+8uSlFlEgTEK>$b0bM`XHgZ;_Fr~{Jy}GW!^H*uLRl}+<@WJ z)T_u`Q}(;fJG2?Yxxq+NmLSKq=b4KdodMr3k8k6gPMrB^cjn|lw|?2nDiTrSqwO$PyRz@w7j4fWcej9oc@@}RqL?x?$c`?hA9LVd0Ni>Xg6 zG^Q)$CLg@!mv#k;`VXDjKqe0A2AMZ{hv)^d3X&g0>_s)K0#oA3%Aqx0m(j7b&|%{}N~D3*D%gH5_FaXAlo!O#?-$e#mv>pwG~dA7)@BdW|qhIA8i>2uuMX zR1|S6WYso)_=@fw=Zt(e#(oi_qZPJ2%DYC#b<05u{(aa9WwRit4uNv#6+QBRZCpCJAmtVNEzZL%A*6{5j~V zQj0~jrld?F3jCgA0MF*qg%etTf;X-Qus}d(v;E9JgfS~nfb=<~TyK#CmZ*$o(PaJe zNLL@(!%#^}A|aRn7P$@#H6WDz!RJP>hxa%qM`6KlC~A5&)P#zff>ckX35kGvt}G_H z5RJwagGHQLMRhAF@^Kc~5BB|WQlZJGm+&3YI@bU4l?Q_ zE*Da%LdEpXO$EN}2LvCWJ))A!&~q~H0L`&8KBcPE-tEf;;?AAe?-suHmj*UOowvYF z6>);<${Nv7hmM+~e#4^&HY%Hc^Xet{{;U6=f>G2?YsWpN{$B!T`e)hi^tv+>k9npj zOu{5w@cT1Qb2)3Qylk{Vr zB9+WN+m;DbS;aHgPa)PN?DE7Z^8L8jLxOWEHdF|$H#yx>0`TS8jhOhjKncErKEoC7 zeM^ZXRUSF#{YFV4l@U~1=~*NRC(vPb9DCn;z*voU=wmPVX z&5OL*T98IHd(g34e>YN9(Gs^~!@G(H8q`AJeP_51S_OQ9lNOk^?YnA@C^5~36|cGr zr;nt8N|Gg`yUwshYg%hYxXqGg#7%1@fDy)_Kme5$|F+@7pSoiQwuU=Qx=Q;y_LnNI z?WCZLT|%@FW$su=C((~ufT`Dt1+1Roki*%b7(pC!aL+n-m6@^`Y5M}cCdW$>pORSj zWZ!7ZKKH@9ew9|BXz<8c4FrVr2eC7)s&Lc#47~HFYJIl$MD`@ z;(Q?7zDr*><&iJAs;V}+KUCB(rd_%Z5|xQxljnRv>XJ~Is18k?^K0(*om+10k{@bR z2w)TAgnAp)UDig5d;Z&!6vf?Jmbjgp78*5$zBUgc#Pv0byZ>#xkg3-V*zXDjro%giO?nSXQB|ZvctO zeS)#&-;s0|pbWsxi$O#U=lN2FnVI5@DoHS@0W9%-K?yEgM+i`?PuF~XX5U3F3RNND zT)s6-2M9LkJA8+MI@C*ByKa4k${`Y{N?akMm(xdG1wAS&Uet?f$E-z|1vuBFvZG#- zv(gj?3V{D!1IJ1%ialRaR%z7e8&~wac{{-(eP{?hT))mZ0BCmERjmAA(XJ%^v3-{Q zDU8e&0@Y+y@t2uqnh6$jF$ZE{t0uNi$~G9yJhH(a2()Y8!_9d7Yf7}SzfK+B>#kis zC);(U?u;8edbVhD484W|*QMtW*QQ-(RfcAN;_Cu4Yd`p*DDm`^PkQ+C8iEdZd+71s zP;zeZ8-J}TAZMcl3VlhbXo*yrdJPyYTZ1Atfgm)}>5qQZUA=V1Eqdc`T(5p3-S7#I ztG$4JCVIZG_4Jv|eC(_8dGs%eB6jDN8#Lk}H*@~i+^R+26$nBQYQd|2F4{Kzi4Q&T zbyd8W6^VGx_6_f;B|v?70UQMCDK-}Yxr%BxY}CW9$AB^J@b0y4|E`suq2l+n3{Pel znLjwstSK5B!dMzyLf4*yT-TmM-J!kfM463#qQKIqmtA@ec5|NkJ=eL%AoUb4di}38 ze^sZ?Cjt=ff#!$$CZjZBu!y)%i4>(7{{iJ3Ai&rXSPX&H5sld(p_&IQTA7mn_e!u{ zcqeIhu>iEna9xP;)wF4^UegYpdMgQw@5V-wq`Y$Zyq*{SP^zl1U3@Eq*gx1(FVt3E zRpV;MKB`%lhxe{`d$uh#VHJat(KUtE9NB6ws75ul_n`4^@785*@7ATh)hBVL@_@zM zHAjECymIW+N5AaG&-je|=Emhem9L*V?~AI8Q(4qlv#jbVy_cn~_rM8mvk)!w0 zv?5~K_`QO~to@fXBi<(~q2A!6PEXI?v`4?JWbLZO-*cDFpG<5?-@X$5Cc)GS?JH6| zMG&cVM~4s-J&u5AD*lKgLC;0>$L5CnOtdvE#ykTwB{LIww z;-+f)@ulVmi&TdD4W6hZI?wFj?zKiiz2~2dBvBrae$QX?-~)c?SD>hN+`I;|IoB`O zISip?VXh<^+pTX9>KKml>ZNn4Tv2tPpRA;~OpWQhCS-nOsB;Wpw}0obTUICzRLps0 zrguW7khjHS33#KQ#V1h_6C9cI%_7r*g0Myq7Dkw$G8=mD%j%_KWb&kENED4{Rnv1;9G9bmSt}I^yf5lN|ce?H{9@XkBM?hpo3_Psyuv80?1m0 zszd;9{qmpadK{uE^n{gHDr*;1M@6Ub%9a>M)Jq?J>i1+Y=pEpvSHDpjSpDI<-%@6J z_EW#(u3kB>SzCxfKp$z>xu@H`X|bxJWW?W^Yc6JSS6Zdt}9lRGwa7Yx?*Uel{M;{1*jL7 zm8*|545v1yZuv`L;-&U!VI07WGx( z`*fX7Nd_{hI7E^lI71R0nSiM|*AVW8ecY-009D_i?vSBYP?oq~%b5Ci1j?qU*=^jQ z5i_LzNOhb5lAx5pn;;z~LwR|P1gtp!R2r!$(X&Wn|D6QjOeD*ITi3qh9{R*@tCtFJNQGd`v}awH9)qP&4Y;J@h2;N|pZ}e}A~t!{l&4gcWav48 z|Kx{1r~L-lBgh8;K@Egi!T{`9PyDt5XavegqLJVrsnNf7nv_1VJ+VPJ{kcS{1pGd+^ zGX>R-QS5pR9HZ(PiPr!YjX~3(xB+n8v(E?tQ^1KTUbLG)H+Bt5Mp-q^s(1;M5LFgE zr`4}UA|Vm%b~H}J?6TqjRU}Ik-#}lc(n!S-yH-|NBmY6qJT~aUnWLgLvp>XKxqDl5 zXkOF3&u}+#(&K7T!2g~+x2Wa2qKE+{FLDm}DM7z7Ag5hKa}CTAcfe6HO}4E7@X z?UmFuR;Rj+8&Esl^&U7@U>$KOoxym6#R*vN&)7H6dhuV-#!KX=O$$VU0R*5{1xNy*Hn_X)#KG$C_|U2oiN{Z>eAO; zzkXSBuLcaCt}5YsKlxJ`N+@s0oFhoWp`?+VU>76A0BAYvyLUu`Lz0{ON40LqsM%6! zJ9%uE+kw()hweJW(EGSwveR6XDQ8}mgG8Z?bI9LuFhgdN0GSM8H$($Y9aKLBbL7aR z9@@Re9XYr~N~IHLzbG0Wl|v{lbD#MG4Qd9w@|p11=RW&y-MS?|QUEjKv9Gx`AADbd zH9=GVp_AOe+L?Mkl}y&BUoDN&Z6zs=qric$`QRlvO%wqE_$Z!jTJf5)sVTZ?p$4Rd zU{Ma-)5MhJ*60;a#s>wSt)^rXHo4g*PV%ITn02P6Hb49f*#!@7O~QEMg2qRS{nS^tOU!;ye(H4IDYkb?VwrAYk{F4v z-1r%vatC)=WznjaMq`9x2MDH;w`=oacOCjCRXj!~Rkm_f)vZInb1A;3mtCa`&d1D< z@r{5;ez0iN-${>rUP+jeq7t|M!&lsj_y1XI4G1K02<1{O6`{Z0gEYYNfMHYI(6Mth z-evFhWnKixs?Ihxqvb#)vN7I25*rx^MT@}tkx6ztch}vyeMkFeC9G?7#xcDC=8xv9$sQvanPdjvd@8!$7n6(fu3Tx+Omm?QP;i&r3@E!ntFr1md8P z=qA%jZwi3}{U#UA92cbp!wCKE-JkraL=WgG03breL?NwbpW$xXhWA`)NvVvZRf;T# z(Gd9hyUO-4pQv^FF7D3F8?Nrc2^(r((_Z&RrV-%Ps&z+YNvVz$6_=^6geq(3^D@OZ z%jgh@AiMzo{LsD)a;{V|0Wgc+_-kcpXFd7b3Wk{ZQ`4rid+3SZw0?;7?+JJUe7pA= z=9azv50Yb_`S@?T%`0A2mJ-@9*}>6Mo|aSCx9vkW>EX{RdmgA<&;SPwpXrwT{BI?6 z^T;RvK#E=~7kp3R3j$LG8=)Kkt2w7DAC1)qKm=Jv{mdT25}Zabv``$WPF}xqQIs+h zUb+|w${<$J=!li3t~=p8G;^_}%u}>YRzD;&^Hvt`8(0jW#?NB&6-9k~afxQtu@;<5 zf;lQSBwg+qEc&md&kzwBsAq_gM4&rCA>!E(v{M}+6Wf32WY@N1FNt{^*tODKy?9RN ziurQ%ig7lfX#*soAC*>AsxrzDW<)YjN~M1h6+8kSl1V}ADD~L9c!q^n_P-&gnhPA~ z47{?cq9i0j->H4uFDq~iL2dve5hw{W{PHCIvX4%ZV&#Jat((p7>pNt!oBrsRCE{@V z`Zagz#9jqoD1uU@1ITgq=`};F0-HwhFMEW&i?Uk?z+h zh@xU8p$Kw0Z%|9QcB{xQOK%>P36i6spWY)zqpVBi{1{Kmfrg(DofVNj?ox6Ov1j5BI@+ zp!K1$4BMq!&mqz_SopI)cSjFw_Vh{<9WlnpT~*#DJoLPLJ2QwaDOfDUW7ZOJn1j34 z+B3at0D;%Q5NXw_qq}|QhP%P2q9A4#Hd&XvBVAr5|f#l}0CFqfrx|aOch( zR^Jy^VwJ^rkrukDZf}_lHK@K6xgp` zI(hwVDf^E(wqtOsCr1b{%TD~{7?J?NY*)J|}wG$q5 z1BXr1{7?X9RJ^>Gs$xc*#adA?=wCZsF%0%>|ISrjrz2)VMG29nVwULNGr*dUMM4EU zQ`NfQk1hCxIlf;Oxn&9SM1yz1SMcD4_jd)PhAPFzBo8~2V&)B#1@R1(t(0-)ef*MP zkNTIqAxlhkG7!n^J?kF;%s}US`^W#)9Xq(mRaCTc6K1_A`VEyqn&_!AEPMBx3Nq=b z!~qesGW>Yjyf4cEeen9rBbq^J#|EBZdd(08UD#4wh@J65v8RII3A-n?Dmx7e0(ybW0N{Z3h*pUk#ee=SwiTRzcY z{hFqtso9W@41YXRvf!hW@x6Q=S#Nq?ND!d1mQ=e7`#b07CqAp$mA&L6v5gfuH^mlY z==-Z>GyTmFXqBz<(3BVLpM^q0ZzLLBQ{=(**QXxTs z*%DiUA%VaO{fku5Zr!-O>mX1+6hcR1=c!c^&lgD(ncc{XwP6?;igrux;2YlimIJ~rf77x z7%b9f3797!$8HX+ou;)TF#v0TDx}ul4>niz1Hm#cWR`XAa_+(8E;GB<2voF>jP`bR z>p++zO`j_OnS=u1AA1D7pM*K=`@@>c|ad2meF-T5Z;e0vdSoli8gNZl&7TF zxn<3p?&Q&3-i~Knt!IkFNz%qEi`+T=x5@ecIeFxi;;)XeKC$PnZjaq2kJ-U3-yO zbQ5O3Aa)k5M1WVTv|2ysJyB3I0At%uJzU>G6J?j6(H}pwEj8k$DIZiY88#$bf(AvQ zab8mw(8#}s^^8wu!B=|^-}>OKAH@n3^&T`Ht8JehWorDN6AnKF6M>!(L_jQnZ9H3$ z3oH&8I@SH;AO3^8dEo%`_Jf0S%D04!?q_bVHE-K3U! z`?j*h1UK}>P(ekA0dR@~B*P8ApKLGLa103Ta?{FtYYThR!4rP;b0QLIfxf4oc+%K?LS<_ZC?Wo$G zMx`>dDmnIK7Ud=^TV{1Tqk3kPCWI;M6EgewGWXHH zBv?#V2JhuMLWL{zgEdBw%YBZp9ce{pUPlFM=HtI1>M=hg9H88j?Ap5S9qm&a!Q=(D zlGTDB+FwNFr$&sB?!9VN6`;rQ&Mlv)RF$aI)Bi1qMoCq6%?p*-I#De&Au$0(jc6$L z%H8z!KwU*-tVDa3N(8-J2;ESvvA!>_)TuE^MzO@c0DABXBozS}6J~ryR969n!#g7O zMrJ>(SSXAV83_G$mi9G4GGjR+p^+pA%3J9zAPDo6P$<0ZJNJ~D>!k~)eZ|!%hatEN zz>4Sg@YBC1#tq3ye28Z7Y5Woax_<}jc>AVkz7rpMQ8Yi=ILaz&T(ACPTu zF0+0_Row{WgW9#((7cgEi@;(UOs4y+eaMs110Fy#&ytEYNk>L}Kt1h&-Ksm|c5nSa zY%1nAT1y4hRU0>DR7k5#kx*a+3ktf&4s2GX6|tnekTz9#$$Xv}6-eile0%h{KXjdX z40Ls8kGZ#A`Y-O>sr^zA9y)f88#;Q96ltm6$Ng`1Z5_JxbE79csXe{+gO_Am)!vbq zubm=>c@R}dT__(|B#}w-1)Fg0^g&m5?u3M;sOkfz=^>^4h}IEf4Ar^)yH-nAp*|#i z^Tr;zz_m|*AQITBy_gN$2HFi&$fY%rh=u)H@2af+lzV) z7}Jo)EERm2*_$=HUnpdU$yCCxr@!PU-~10YU+Kz#p!2Hkrd$(uH5^>r&UD=2b zdGl}G_Vw@S8p)2+cL-QSVq6wW!mbUXoI(?2w$QFEi)AFB(LV9QA8V~>&gOMgGs(7* zl?SAv)VF2L&(&)&?a?o~H^29Pi;hU}GoW^coBfI3c1z#>roiIUU--Y&M7{Lqe{WQv zAgNslP>gJ43r%H1g8~Rj#cKQ(Q;NJSEw8I@du`NMlRC@2E(b?!Mx3dB%O zQMDXcJ5{R5s}}!2vldCXB>Q8+nj?rpRg~! zECP#q#tB+;((zhJDyz4&sgW5i18KR=ObdHB{3dJ3b%gh10%1$)Szuz7tlTajY47s| zhMZ}V473wyR$y6~m=cWhxp4Zh+p_L03Ak`Z)$5%F7Hu{kKLn2bhfGmF`RS8;-H!DO z-1Vy$lvJQ1C@Q13w_F>qw|TO54`FW=sbUD@qu$lu@pBlN3Q})2u)M5FuP3l1&?a~V z;IN+qYa{}Tp28?iPOd>CkeGMcR^R~t0AM<>bCoJRu}2KTCt-1mq?$T>{A1dK0Ibs| z_L%~w2ZkAtC+nd!9W16Pn=md|BU&6nJ4PBh31Yjp9lN<%Pki0=9Wp_FX6c)Mr+d0f z+s0k&wy*Yh!4jTB@BX9R*y+!?-CLGw{vfKMBgQ}Oip$E}rsc1QA{+;+rlK15koG_l z3^&3oDL6QZUg-C9F8`IqEa0iys@k}hQqepSJ3)1vfS$dqS&gcE$ANc9*l`8hrTau(y+6<^`Zd~~@F+9Rv z;#x^=!)`*1Xz$kLZs*4L1)QRhPr)CXLreT`(>u-Hk!jOlqgA=F)1Gsky7$-mkxYc* zt9YuOdD@k3*tmJ}4fL~eo$MX<7>c`$#zAMn5_!4Cur*SNg|6GVkDD^*^X}S}^8$-% zo${l?GAWLwuYSoEKi!zLGe zB`Jm59DXO|7w^q4<%5m)RFQ4|p?~m>`?vxh30RD&Z1K)cf<-8$RQF!_r~h377Gxx$ zrjDQa8TZx?|6e!h;m^q+Q2C+)LH`n}ZB&sMF8kEy{}0W4WB4)@M8q^6fANn6=rEXb zp7}STuP%H0o9@;fo8v~%iUVdyec!~Ztu3G z>Jde%e8&8*x}|UaPYpeP{DnVqCy(uxf}iNYq4M?%0*h3Lp?g8m(tJuU6cgw#5$I|H zEJkjOkqjkedJgmuv7hKEGu8BqifG&?f^uzzu2(T8+i zp;2e*?p=3R1Hj8%d3mL(*sLeYj!>BI2UsLo1C5k%7gU8TVM1`+AX+KO2tX=TSA-Hy z9p5cc8nW@I0M@jo7vsD;adf+SqmXIu+H;6ov-l+qyYXjey030}cSQIbhLHRoc1cuJSdOV7cGU zIlq@k0?g#A?3wytFIDA8e^y?w7=fE2S5{f=hL3wx?E`?XOLZq@zpz{Mj>D)>HB&$@ zp6TYFn7e%oYMLpLGP{qth$tX$UH6s%r&dyxEvk}Kr44xS6TnCiRskTg!}vV2-?ksD zqG_};t^@y4R$1i+*UoS~2aFL_de62cn!}eIp<~aMYqw`6rS2kZO_?gFL&rWM8XW>J z+;hCOZRG;(AG_PCO=mZJ!lOE0d$ulh2lpVEA17lnS3cKMZ9Hw41J3Ixc#VOG&TY&h ztNInIk~?Plb8hUkXN}_c;VW+Kk{^juu5lPJQZm3IcZYxovxw=Jr{!VDs9B;PGb``F z&ef5SnE|YS9bgfE-?jHJH+lApva2u~0KFRdLE=FJ>_Z!=DMee)+kExN?c2W0?cKKA zC$4ip zKBL%a-IAA-U=DqZ$=BtuY6W$i+FqO5-Eo=J96@jiWg05Cz%zPDSw`1`89hI5<- zi#FpLd0th>R6J5JM9Xc6`7HIE_EP*tEQ%jvlu(!#U8qMWIBnk?Mp$!V z!TShE9(>ftcLlP*VpcCuW7i%y&>1EqE{-cSCA6uO3tdBkmA`I_dhk)a+v`6+kinJZhFZb$FMI1@nknwd<4{BzXle#56Sfu((87F%+?G zF&nPJ6k|Jg8|coTIwV>ueN`9|=o17m^j(p)C8G@3qlx?dpZ=K!Jo7r#U=gW7D1fXP zRZaq+{X0Gs4ddZwe&3xwx?3uM%mtzkjL{kUwk~r!HZ7DxX2}_q!S&HkLZ)%y&;C+9 z5|2OsAKlUYo89JBKXVn;ZKXmuXyi<{==HzSHP3zS4;7>Xws|hUXs{T9>xkYLvDd7J zH1sbd_o4xc@MFKr%y~jDQ>B4yu%G)0J(6k{6^!6ya=Ye4H9W(p2I@6|9bg0+R+yQo z>j+@P{*V#hWqw=1rakpJDM0F+SCT_+-kEwJfnG_es7VBR#}Dt&ezl(nHu*m_8It&S zc<5AI>MAO$M9IE=gDOdb&TPkS1JsLzV({4$d)>j^>jVZ!z|fmQHXfzHYgaC+4+9|) zp4zanbG3&zeE5n2uk^DuuoBVr{Q3&J6ctJMg!9yU&{%;-sN$C|o)N8@eju{51aY=I z{60xOpHwuIy$*$f#qit>m}CbhjZ;FC-&<%%aQ~f1CcV~dboRYuezU6Di4z!8+zfz0 z(H=NrhExsPw(I6@+_FSN&<2N%enkE608^;`uvbDb9k*i` z;F36+z(KKE6G+Ul|7Zzdj<0Fbgk2Q?nf;ko1I_`XI{;QF21CnE9of|4H$Onl*TWY+ zDYmhpRn100(K|Wo$=?wjm&z20NY-9w(}U|wu*kDuMlb?&0AH==;EC?+sRLpHVW%vS z<7dFCs+$}Mk~j-_Xs0c)o>Ap8sG(+7rW&F6vHXBRM7btB^cnT8F**g%ql7Z_d1(|_ zmDOVav605j__Tn=rWHTa$g!;0Do^~B`=r~u)e=!s>L$#3K}wyd%TrZc{@y=&yN4KI zndU_!7`AHh_uaV@2mG;s)l=<8PJBY+i|A+EwP~^bEvu51^CAk{f5uR-Jk;X{;umkbc)8@K-Wdp9lH*l9ATuegtk(ZAj zXOOq=;7N*;P%S1dlvm8LnGk3jGG?|LJaV=woDvE2RrLD?7874gY)6X``{>AlO`0jG zczz9^)G3ernw-kc4GYvj-=;$sjqTviyEZR!l{IbL zsL4;cu001^Ngkn@JGV3|i$EQxjKKpSk%0o(QQ4?Ff6Og^`WNTZu>!!e!jPd1* zr_}Rz^X3%|U1r!Sil>siOX39eQq;TBifTzw0|qgE1UgciY|}}Do&kjPO`_gK0E_qn z;1Fj|Rvk;kpAiB=0dUz{-;ne=v|0?;V!bst8nLS1TGGN#=i6`LHp;IuYjNXL9`!-2@XvD-Pq!`G&%e?|0fXN|uWi+)gH#H6_EOsOG_feSi#{*e{gI%d z`2HlkAY)$SE<#^!2yzqE%yi(J$Pgzfq(w#6TUTGNy%^Dr0%b4C&^HAZQ)s1NQJGKSmiEXJgoq+eWyOITd%=769nBPgrKm7KoRBRQInoB|SK6W^T=EE>Qs76o(qW54ctKwZ9Z)m^!8%3Zp6)*aZnLKPP1 zWHw9BD=zv9AAcs$MZFp321&x!Z8|GhW8?sRMgxb>RJD=)%}hDw7*bVcu3ua&w8WB< z8YRZs@K(Uoa{aJ&3mC(*0PGEQwPWWg5xHyABK1?YZrjxz+`C48#we!-3`ok*GJs7u zet4VIu7^*2!c|sOtLO0O!L14agJgZmwyMXnL@JpuTu7p9U-!1Vc%EJ*6ZFZqZ<-61 zngWXvY0w*Do&mlMcFus|Gj!hze)i{DU)n3ePm;8+co=_el%2% z>A}RG0lZ-VInB5;N^oI7#jH|u?_V}0q&8Xz7WrPlGm7KbGeCsI?HZht!uSLw>wJZr zB*2IXk10+;)%L)i)y_+{#g8@N_zJx%*+51*bnfGxc=3<42kB3L=jH$IP8{B5kAePi z#9SWzb+Iu%eE*-_wM%EUcKCWKY*ZE5b5x5tQ}mxE6a0E2O$KO&0IdnpjCS@I)SM^YfCoiFsM@%;~8`mcKhBCrT(BkfD=z(d{XBa+r8o7TF0SG@*9 zjfe)6Aj|hj<4kZLaK}D1AVqM6p za-Do8!NT>cm)!9~TczrS8Y{;4)Un;JXWtQ0^9tEIQ7+3W+^&ra)KduEi6PEyJ9Kpy z&K}b>i_&`Ww6aQkU)Nqkl=)*WBlC!GP-LDjoIav!;aQQfr>6_bEP*&662S-h70Ros zUC%xvmAPi!=;NbF|4Q8{T?@Y$fpF#WnTSGTi|`SG#pGv)^lS3$_@-;FjbMdqXT}ZxGN{u5OV8yckS+qK7F ziF>feQ0FB;2y{QP@d!4N89#Gux7)Ppbw3BwW|BpnY8e%-P%UPx24E8bECi;QNyWKr z-?68HGuR1$WcnFl8ek8wEy;j1H;pNN2vJotBUwOLiXmhOXu9-{TnoTg8phdqju&Lv_TJrGG1CP z8Yj#Ps&n*u;{zB|u=tI?mff23)bDAQB9wka#}KXH-=UVFLMjTUSEw`rBq-`7Qt}kR zvZzQEa?xL@f-)zt;jR)7B;dOC8s@62+qgB0e;_;CcgRHbI5F={bVEK5N_xj0u2;X& znybioC-yiX6A_qwJ6HOF?s?iimDK4gMQr(oO^Y;2CSrKxeTXd!P&0%7d^H$+C`zwa(yI3D-*`eY>c&)Ai2y=t{D zNMdYR{f2ySlE&;ES@VG}Eixq~Zv4#W-K5zsDz@3W=1sT!?SF8$@7xqRBA!BX0kDYO zgGNcxnlFR8KVs68u3PWHZri$djn&~RyJ@JEFAlI2Oy*C%{bWbnUQfb)-1JYnuDxod zE_&k7R$V`g01}QUy5d7NuYO%~lRYOy@g2#}*-!tjt2=WIuKvD03;~EHzjT&Oozy$>$iDXi)W0Tc~6u@Ft z8x5fcEWYu*|18P>m@a1Dt)4+Yt1wWNl!26Dq6Inp62(Xc2}L?The`|x>lwf)g?|rJ zB>HD?&}6IW$AC_%pvfD-V1}SUP?00+Lw^PVC{-2u)(CE{U%%qcpE~R+t7}}xuKiWv zprXMXCImr}J#EFMY{$A@Bx(i43~Hf{T4V-UWXu2tbCf8?XUem;2)l9$Z=QYD9`#~#0Wwa)F^woFcr?+0j*IDt|_ zr5$RhDlV7Lr_^ZKizIqb>_u*V)uQiOFr(~>2a6d%QR=9bHR|0RIAXf1tZc2Z3j(5y z2x(x9N|mZmoqG(@HIQ^6nLr;1VooUUk#H~?ov&!+u=&w*Nr(ZY)*%9r_H?strDgw9 zAxtCXkO1K9Ttj6u`_(v&HU9j9Y_)%R5*$X`H3U{>DE+M5(BGLWIE-s_QQ)YhurUjh zAO4(Z#t1iXHrb!pMd+sl&t~(|J|^@olF(x84@jn;jaOS_zXEuusL&J0oHu~wwW}9gyAD0nFNpuawlZFbJ}`g* zdu{o<|K!?t>M7xw)$~wZt<%4;r|6^SIT4gI6SsBy?(WjLl{JrdsumDAMrN+cfe zL3|(Mp%{ctWgc2?v~e1#NVlxAriYu}lhFqCVY&CAJqL_-bD#YK*P&Bick1{qxA^tH zai@;#jQv@-wyfkIlSfM2z}o3<$jDjpH=Iu@$@F|uQN)Im%rx+hfDbJYai45lZ;xt1 zStqn*_n+fPMj+m(=)Rt9mxSO}Grs|xg4&R{ofc;O> zWXtNe+^HiwOrz4i~nvbYM7;T7buo!w0Ik!{`smL;mn$a}L zn9t$>d`K%dZu)a#f^A&!n#NeLXJfFK9x>LEy%<)8=hVILaK(&nPRq;I+RH zMS?Pa=1+<$WGEpoMJjxk=4vJKb@8YA>{eN&tEy_P%<|1^mo#*BQ0;V+jLray7>R3F zFT0A0D*Zd}xp4ZB4ePC_QiYGegPsIcG^mc=ydjVWMbIcw25PxKs()m^0e-S^zTYME z-w@;w95G#T$ILj$8#rvLgg*f3I5#Tk0BmU405$e6DyKXTGP8(DWeP}<1fmj* z*a2ceAHMfb>SglHWEQ%3@L^Y8Bqd~e6#EUH?8+)D-QnHq-N8MpRiz5RiUf@MT}w(; z_374Qh^|Kx>{sigyh~3bl}4)doKgByNUT^gg5Ifk$M89tV_8wHeZd-su?w1^2BpUb zLP3$!s!lK^Dot?3_p`AVZr{4*1um!#lzl!Td(X2|>SS zHYmawFg~aP!d_txXuA&GwSO+0J?vVw>7wA93L}fcSf+kMCcAOdKjn@b*eKDLs_Is1 zG1$KLUG+}_7BxSz$6yJrA!x(wJ)6OpppqtnH2edfOOF;{YR|T%qIw!=${1ml11hyV zK+WN?gHo)ojL`xxeg0Qf6$2EnT=*TgWBq$JS2oO-%eOBz>aN5M8a_=UKv1OKy?L=a zb9|p>sRru4RcG1ysBeq`o&P2bpM0S!9!1c-CaC)%&q?52eQ$`Cn&Sh15DxuP-axm?DXKh zg2k*@&f6LE12~VU8e?Bi9@(h`%aDtmtB}$>DyaZX&OB=NfInFx zpIo!=%K(c(H5JfbTJEOK`;xu`Q8ij|a)Cv}f)M1QznYdEV#J`eVRpHB&n#yY?avR1 zHMBMu`$cRB&HH9zu4>Z}cmc1-dsg#RjtltA2QT@RU4f#W{YEzgfq^K%Z4PKCaOnd0 z4MH8X(6u#joSs1x{6;p^US zq#HN&8BrK>RYI>{zbu2QfU%)L)fx^tvpmi4WNhs>8`S@ZK2Th8m3?bqeR~$s-65P{>+j5SZ>* zBvh4yV~p=R;b45f7J;6H!D)j^Ak=rzc=bt<0hHW-)CZZ7mdLo*bih-1_>Cs@JRBB($X+`w96U@?84>H0&1yL%TUVH8iN$drzC*0;@xjaDbwg^wjZJS2}lW8wsQT4PF6*e z`)2*2>;Y75oI!ZzoHLt$$@RAH*h|2lOg}Rk0f$iE2n49CLthqPEGg07X$;PtTTxaU zJ5|%RgX`L3sH;1BMDrb0xoSt{s=IpYNM=w01Dr5U1zI@Y%f1X1LiSTdd9^!!WQV?& ztUuSp=VQA_+92m{z}hG5@>DeoG_^Tj7Ez-^uW+O_2JFAlNp)mH+wZ_jPV#$ zi`fGN($_AX7b{}N#`m=k0S`9xJ06JpIu-K9QkX!-y` zdexcHH|xpYQm^Z#6|br%ecq@4P%4m&oESIr)3P1(JuzN|zRAHOW+_Pri0eCKk}8D+ zX3V^U{x*HymsKeQfL=IzRFe6Kj;&k%vKu+!aorO%Q7V9?WtF0{VV{@3`;QuFH0hxi z)K|WB&0CraO#i%9^AkV%GiT|J7&VCCP(9tT?rj0;$kt?LShJpFOM_K=Zdnja`^@Gm z(vUoM>L=agN4}sLr#m+-Qvd%IFG{7kioyP7UYEaa0AQCM1Ko&;kIUDRm|+YE1JI%A zN=4bcq)((;6+JWIk^FN!hqvk7pBVy&)k?zTR3EdSkr?vJfU%l39dyP4$k+>M7Sz{k z912-;fv&eTmpn=I@T1`6+ky_K~Fhsfy za(#zQbnQCylntk)fVLjSd|bVBHd45!rGexP?5<-6w`ClA!gWNntN<33ferMTM0gtxM+B;ZlQcRb*)@P0SvbH2+2x6|o)@J< z>K&=*yg^_^17lk;%Z{M(q^b~rT^4~c9%Q;`8Yio5*Q8Xv|D^aDsbHKuywh#`@Tb0N znKKM!;+=4IVLw%Qx-NWRUi??>CW zn6bXz;>UmMlLHdED63H4BEW(m0}1-O^)~oegOa(ID|H&zfWejUOhR%#nHaF_V4UfX znJYd}3NF)AoKx53`&u{~DEkorAS#dqiz#5~<=`V4YQkVQubSwofPO3G>I1d_Frge; zTVEhw(YwrFxt0$g}Zd&gq{g| zinGwMb6TGU9#Ra0s^R|R1@hNyK(iB z+rMk2DjsC~`3?XCHpCdLP}=TDAc@f$R0E;F(*H`5q)j^;dxBap_Jp&0;mlD{m!V^m zoZ-F{HruuF+7y)K-+@)@RMC_Fp$Z} zmOeu!xM_30sKD;l%`5Iw-C6a^0-y-;*em%I{zN%Zg{kLiXU~OBs?d;YseOVP`0Ncz@{FbQ8@BQ>o zHC_N3;X{xArdzq-+p4aRgqZ#0@3=E3_Nx~Pn=*Rp({97EpGuUecHCS6(B*IcqdT;B zjh-7y-i&>L_S&QGaMx$>MA0;pkOKF9j$EUk(*w#L|37>09c9;boq6txKmk=Kpis!E02Ff086cP` zQlzqEIlE=I?RNKcnC_YGnbot_%s=C`W*pic%h|FmD_DV|D2fRr5{aC1&bg3N0fh>) ze&0FghF9-Zy$Yfz8E-8TDAarR-Fw15``i25->#W%rw(nB8mw9%$R!B2+<#}gS*rAI zq*R16Z}u`*tBAeXzx_>H_v61%a3Xw#7*fqmvVTjS`3?2Nq~=tgUHUm2IIPxoeekNC zJGEDzNwQ8lGrIYHCJu%;-wyi*D`5DTnNq$dfQDa19Vo#>>>^`JD;fj=2~eWidh7am z9~^Xa&~&gn2^Q18V?AP9u z!UUcX^Pyydq{W#NyX+Q0qfmaJ^`B{x+Zyd00qDnIG2bQn_z&URa&9j$3 zkmKzhoy!?F5yi|3ibVTT(^=nB5F^X8Or7(BjhnX2nV#gH^PrVF8S2=m^}|7h_J{)r zh{3=i1>LKnO7v0J+b^Cb2oW8jS5~V7OxCx9U@_qkb@(2`IAvruLvS5~3Yf;2;ij57PfR_9Fkx5 z)ICYys^4I>6aZWS1Q16dQ>EWk4G}OvI71XUmaST*G^w2i*#SU3>%646r}eI^RxegE zNT?=rNF$0v{Uq-LPy=$IMX^s{6I2ZvsUE4k573EV5R@nc8gAdXVArmkk)sBPW?j(l zQ5k2S6~!SUI0aZ?-*bKT`H&HlMT5L`^RjFlz!)F}?YXchT@#ZW!j9ImfSZH55R*vS{Z^xp)|5AS+k!X5mM^?)5F>)3zbNKqh) z(h>y+sA(h!f%E<0TYu%wEwaPOgT!a=2vQIr0hEy;MZzDu6ezjQG_R6Hb};qy&NpCCewlK@2Y$PIyG6yJsV#W5Dr=pZkKnC?UL_&M2P|qfx^j) z9iF%ROLq6}bvt`(hxRb63+jx?G~#Qa<_>tr50l?00$DaYnHd6gKVw@)jGJRqWLJcYbMqrPX&4DI95{2-!a(_m=re7AoS?u+zn)SuR05$*ssSW( zg_B1Fbo9gpj@pm`7WoIn3d(vTic_jg7IY?@)n2_T1!SoUmML=K>TZ+@A@SRf@eC4OyY2aMXZ z`WApr-vJ}EuE`KUM~#2$ZX~tLGvU~rV&SmXNBTAdcs20-cX;VHVvW&ml(~j$s#ci5ANNus(~Zq zR6<+jc?o)u*`)3nyVq7UxjVpOJ{iR@YsqyMIqW`w#xt_s0Ryv_eMU9t1aklZM99w^ z-=Q`^P(j-*Z73)Z@SiaK2^%?Xp4QXm_y56;?cboigu3r1zWl%2$wQm%%<-MJ*JYryUs;K+v)meoJ=my&wFMYzI9J0gG$j_^QC*lzE@9F%#z7 z@q>>sb5h5g>^!J1XWYMd+i&4o=}!d zjADUPf*d_*p}+(!4vy?wud@U-&fH)zuvEgIZs&H!t#9pi`tXrghz7(ie&*K%ddTXo z{^6gvy&k?S5dh7413vQt6G2TFWdB@y5Nsm*5!xnuknsXwlg-C&kllxNjAAaWo}`lM z*-K#*Q)AT8b0+ov#8~=s+NIY}dG4i*sP08Ahup)fb(6K&{3pJwjPkbi|18}B1me_V zv87qPC}%8s#mXzH?eN~!VjJP3w0fliq`BuZ6D(pU5MCjeg5N@b?ZdbK&Iu`rzMssJ z7TClYPpa;eHWL@m9I_b;U$VXfMrw_pKYc)=Hm*OZ&l7ZNRpmbsNmf}{#mp(H)-x8p zWCymd(z=scZfQ@~5{z1I##qY51bTf|GN-@MI*Sa^6d+hTZK>~@xY`cwTqV03uY?xW zGBdx}_iZ2iv)aCpNle@0j_$p%x8o#C@CUF{qiW|^QE`!ij!u;}Zc7to-18jb4ueHG z1o=YIJa6Lh+kWmxK&>-k2Qub)XMOT4fFl3+hog$&q(Rx7vFK&%H*l2I-??dIfiPaw zp^%a%qC0!ZXC$J5QXB{VoTZ;t#1n3}nzrX?TpAoAcdPF1IIIA3p;nRJUpQ?`pZg6v zacGN;96enMjoA)W?wNvjvRBk#u(^p0^{E^vu!!SF4GW+K2R15%_6Kc}N=x<&rxQ@< zq_kV??#()@yL{RSV0eJjtR}<{++9C9Q116 za1t%&kl_H6YOuaMj(f8vXmwJ5&#C5SJAd;5i;+XG3~Gti9ftw*zCbz3ym)5xotnDp zL8DxK<&DeP2R+MS!Sx3W8EqqK=ct_v^*Tu3Ly^RZBLjeQ!u~~B4}p&d^>;)yR3B2y z$f_j1IRzG*nw06IaWoj!Ehz>okJDuXw!LK||nfea{$oKRKeK$aOMYE=$=il+k^YJY~1uGZ06!uY{NTW6R=+L z{8w!Mwl~$ku4>?LTlw<86G*3(#>_>ps7`hBdtX=Jaq08FDcbS7-~R)x1%iT$pZRr( z*WjR$KXFp@p=YLXQkv_Np3Is5iZ}!%ay=!gy zf|tYyS^w5wX$=NO07K1s=3F4~Ic4s152Q*Yku@+QmPC}-H})AIDgq~r3Z_}^t2SfqJ}ynD#bZm(o<(SXAvS) zWckS)Gfvo5#*04W_j zF0gq|d`Uh7w0X1(LVYzhlOOPW9|6^ytSaXz!6VL_);Y}lJ?s3zVp2RV zfbV48XK;tw_lMf>jHjr|rLos{~C$POS;=p!&oL;t(~WD|A}9;jqm=Q9KzwFXSjpVJ2TpV z5~pbt@ZeyBPKFag1Qe&1-=m0zBg?@yX7Xau$}+)6vJR6PI}}cN*4wx0WF(3 zfGPA<>bh_s5wDEGR zADJ9Jw{^`oB%zKP9evt*_3CTqPVEuZuWCSz_8=5jXro*nRbRm3#nbx*79CZ~shJKR zJx!TtL~zJVF=xow4;)f!m(CqhwhxC1fgEfdwt;5sP;PMsc|mVQ$r11d%@$igeHo5F z*+{6W0GB|M<2`lfkBO>?kPD7D;tWvJaUcP^IG;$eV@IHx(<=~$Mb)4YR)q5Br4y-) zMkX*!0k1afLN5BL^TS+#BUwX~tzNE`^Oc~{xth*GDUBkA!de07L#@AZ?uZ@S{hnRF zeA;F5GbrXs+bX(dVWEwgL|?v@T1SWXuCbA0W?9XIc?xnUFfp)3U~b3y?`VF=76Q1) zEJCY)@|FKdS-&l7z9naR=HgEYWbXLj`!;RnNy4!ir1{MjPL5qe4IBmg8+PA1p(ptc&6UPjh z_8@@!JuQtw8A)rfh;0^|1y)F5u@#q=s>Kd-z!))?_y$y9LuI~t`J@66qLbfudpzlj zWOZkgHRoA@xX*z^7TXAtuiRR2*{so;chj+ebYu@;C1<^uaI#SW4pJ7Q) z&F7$Dc#Lgb{SDRO61WStsid@*&0g|pG1vBN{-K>dvQ2x_1@pV| zFUGMqWKUF;ZHW%h{5W8BKf7cO=TEFv(6U}KXQSE>G=i9lXw zUC+m#`}rLK3EU_e=W8p}dyo1bAJt1P+H9=wd>6EHR_Omn-OeN{Evt}xGZ96i!OK7K zuT|6V&Ub#_Ce40UG_*JV>HktsEc&`ZA6oPJpW4YI+idW#@uEHvmAP>Gfa(co;tW8* zk!6$91CBj6V(e_GX;C9V=JM{XtJ;J#fhCgo!CQZ=T7=rkOT4q|qLY9=oJndp_zc+x zB0+$=>sQaIUIh^q99gJz(40op&Q@Jh@)ZL`3_+0`)k|j%h}w7e)^+vlO9F)a(MubP zG6O8C=3(F{MR0FkKc6)|oDY!c5?IX0W&|)E#5~;jP47vhu8W0lpaSwAV*c$f;#Az7beV{5{;O>qF@r*JPGAQb=tRET(Bo0cdh>$;@`hU~?a=L7buR$~-9B zn_nFo-l?b8qNdH|-5QpM{nOjg&(O3S@FGyHR%k4^Kxl8j9Go`7c<{ zvP!#r{;-`swnJGq#tz4yRtC_f=}XFf#eu_t#!+@P$cYGL4vGuU=DyR>wh<2@)4;wY zV1(LW&tB!K=R#SM`=^mIW0nmp#+gM|v)EDqSag}iBv?eGhFTw5F97TUSPcEt7%S>k za26R`oW&#i*IA422}z)d>=hY7#+EiWnj3R#kPH_BIoB_r(pZtD;F^FReY~Qvw6r7NZe;dxS6XIwVNC!w!=e2js8+QBF6|1ZqBwOqH z*%nLKhP8m2CTn5wv%jGX363x|KjWsakn$>ZuLOahcX0-wT8Vux?NKh;9(D0hh-vEp z?U`sknQ;P>1V*@LK;VI0tD?Hx(G%xO)N1F3*Hr$1g#XB~vlMh7vk9XmWyb#q0 zv2zGWm534YNVL%FSI*ki%f}^-!x`WhB^hN5epyF*#Gip#5}fI$@EIlmAz4m>3pcKu z6{{kEMS?lAmV8>Ei_9V*Rw8VrJw!>KH1jEC!*`-GN;{uC!D9PvWr6JN)1Ubd60Lb~ z_of2q0E~#{nn9O@MKx#H=Zv1E1h0mTnr3HD?za8g-}dU!e%vBfOzSpVt=3E45!LKZ zlw`iBPP??HfMU(~xf)LxWCVya>8j~Wc6{cwb!3NYICr8&tcN+vz91ivRxm-FF8I6H zu-VH$Z;u|_lTs>7FP&3b7hT(l=|rd-Rcy?t@$;>?xL84|b0_z>HSLqCt~|)S^7XCT zyvvM$9c(z(GeLQRulS_Vcs>S;?Qh9{!S5)j89%oLwJnTxs4-v>!O3?onBPIv#{C=? zvU6gC(QbbfUH?H-lpP05MdbsX;^63si(~{5E`Z*I7{MFg04&~&z~bs3{;9wtnMtxs z+t<-!sKK89!he--g4{QbF%%54Xk;d!*5KTZteqn%a0$}%sj`)ybj_UURWyFuauxSS zSv`b8N_tvJk6wzhk{Q6+%w$_p)Wo5bc1|5^P|rFJ zyuxBD>scV@NWt?o=jISZNb%sP+E?+pMIKm~gMN17Tygh<$b)TNQd3)zjqBPUB_ zhAbl4JnRM;CTs?PkSss@$I0@yC=k`NccopSzM0zG!a|?97-r{A>{e#c(ZK<64RQ|I z`(z$rBLFm6FW3o~1UMTwW(cf6jZQ39Sy)>8K?pxS|qr-uX6rg2aT7hau$4*(S@uHOlwdw2~_I~I=iG5_enJ0oX zhyyKs{wua`+mF>g18{=9<$bPp)ihtMf7TC9sn{p=ceR_TBUL}#h6g_LS*QrV=+)F= zswXFPU`}j_bwogr)+T_)@zYld~zirXL5H@e=262++=rl1UT?!qE6`FEuteDlTyyL0`r&g6$)2rdL1Gq+48 z`y={&(kYI>B4H|_R~E2(ml?185IJdz|>#24hOAhXC5 ztb6k>MFm$sZr^qaHUVv!sF{T67TQobA1S}@%=zf8z*m7XzJo?g)LfA0xOVAyihJa~ z)@LH~tSfBA1c?{Ae+)l=EiJ0gk0`i46aN@2w!3&Azky{rYTR7;!)kOYXP0bEldJcE z?%8*c(Qgnz03G5P8z>1D1s-$IYZOnE8Y!8IChO6ow+$OTLlHZa4{3P+!P|eU3?P&X zB6gWz5sDDbB?Za*w!ERJOyBC^_R^RCyWP2c#Q>8~MrSSll+9f9X?y>*KUP!?0fm*H z{5?Cc^Bpx*9$GU^bR-(qB6AJZXy%eni?$b>HKK;S%lnHGQ-A-C^&ebgJxa^eC>k{~ zj0%x!UexE{==H4{tb--husu3#9qhmX$7$WY>4#AbRwh_E1iby6RtvR2@L4D9$Erc2GzMf( z5Y|Hc#{s(ni7Zej2UsDvM7=caHfXJYlTRj+u>jmb--dq6n!9uRn!o}XQP%CHvq$XV z0|a8jRLa&~eYG!{<3bV%!d}t>QY!EHkng0+#Osf{M?pRyUbEnR8 zPWF+#>qNl~Vj&@-?^pv)C?z}xKy~FSu14|5p4A#N>_AH7LuEk|A##&?z5TIn<_iTP$z#b=*>@isjKr#Y1P~=0ljGA6*9+^|> zDWOw3`{ctVa`dy?_%6Drsg;vS%Y&K09-&G3#2HWNo}ixY_~3iWo~G%}ZD$tUOvlzL z$}EPSx2axs?zTd(DE!pQ>PA66Y_|h%WXTA`vM)I&U?V9=apknK^aNy-AyG+!FA?yg zK;Wkp4L=1I({ljDyl2mH*$wt5feOkYW-tD%0@d5seaGtSZ^;LlI`0!w?}Z_CX!rZk z_;vKW&h~!hfdJhLU;JNH<3?uv-B!PQBRrZG$im7`xy{2)a z>_YY>;|tU4E$uzHfMoZ9Mb7;R(^pD?{@DHx?9k5lbT{~fxtI<)*GiUwb97EuJB%Lz zb7SGtzpB<-8{hky1B)JvpoI=wJj$O zZB*~C>GNL{72y3J{GlkNGZwxqu??~%fszYV3JN52JAei?lGKk~uRAYC6ekepi35@d z=bamutY>*&>s8iAbXEYS>OxA(S{WcBq|`S+^K*@Hy`V+HxWq=PagYVXVnw;UGdER*=F2x1pn^$-$!M66$hfa{!l6 z`EW9sOU4b=LIMOtU&#QFS%~^lA~4dsQo#+JN!2I%IzkP0kYvvV7DJ6z!kjWbWSx5T zsH`3LuQ?EB@4q?K?7r6*qbPV_U<#lnj0JJ;<-Z#=*YQO9a8>aF%F`b z^&d3S#!gvggNM^v;*OjxsHO^1xecK^W)Be%B7?_4PR1VxjtoD05b!o|_;?BBIFW<` zH3l#3Rbh<}>lK{gN(2_}+`6VUL8}F_d}=Y$yRWFaD0l)m5!S*vJ+S>vDG8E+A-iz< zMxB5T_fgTOO7vOAALrxFtt$e%tUs>bw`z#QbEtiD*-#i2?r(a$Y=e93_*!la%02Zq&I2MZbm9V@4s`G$^Gt6<8l4~7y+(mPKq0lKwbPbc zzy8COmC$)a2EV0Qy*Fpf|D^TlKg14fdt0Jy>>dArt;Q+SyXcVZZO1i<=3bNI*ez4$ zy;TR?cz8Gb911tF7!M z+B(jCW#2(kBgcNRuTZCks*0-W-5Zz1CV2P|RtlNqBCnX80T|l=i`)u;hI&o}jd&)Q z0y7r8te^&V3fo^bV7N_~@s!=Wb5)dNfGai;CI%GsuD)2iGnahE<}LrCp8xQ!Rkr$# zugcDcpnN(wuV%B>tD>L4B7s(VD(~9xswnQ*rJ(HE)_P0s|FECCXFa+sDE4#C($8y; z(B|gm)w2=h)9sJQRK{mk2Yitz*e0;}$cBxYBHs>yDk!gRj#%G?He&1y`F`vH7rf8R z3U|+whqDYn3>rHOB?26jdSteZ$@IxO;DtHYCKU?E2=*ju&$Id%;UDunSGu~!AAkO5 zYXk~v#?NnYbxEAi(11!svBY`7Ig+E}7Y{}YbvXy1I2bcyRB>D;bCHLLB@Pu%EKVHR z0Sr2a%8Uh{RQ|iMW#Y;! z`bX_ZoPwlVO9Z~76vrX2CaDB2qIEDhFQ9S@O zwMxw=byBYQC1gRIbL8Ia+i_$%F)c3B#kFZb&l+~0&rRJ)?~vB}#hs5?Mmuv%J;2R; zC*wu74dqUvv$_@_uX?x?N6CWTyzRylQL!?4WHkUy^eg2acWwNEqQ996cml3Hdn@Qt z!rt_)b^u}QH>idHx5h{H0v!a4h^_;mak%&yaLF_&V+u`u!aUI^*_$~3Cy#7aP=Ra0 zGC=I+@b1;BrNQ3eSm2~_9Y6#WS|_U2sDGnzw4(N&V$Xb#)h5%a;F}LB@NA)#fM`%i z#6Nl{Cx!cp>v!Ec=~l3)3`_Ppm`oaU+KRK6%Eb1-u_7Bs@PS%YXHVD2_97}ic(A%_VdeRThNiH-r!*h|j#A}Z#9V^pK-feUMgv1frY-cZ$1qm1s?gGCo0 zD9{?7!fK4n%XM-g_ki6S6Un z9=afl1lGzG=o~R-mYqGZOW70H9Qr;tscjhZ?E9u;)<6C35U6vkp=L1zsDXoa&3dP& zB=w>}kfTEf0yhyb4xp)ZfWqBnc4s^Z7PW@FlM8TU4RGcPI93gjeL|W1A?y(v zxL>~{TL#+)g>eN6Lm(jxO_oC)A&*E!z$9zA&#?RLXh=$4`@<{CkigaM(Y(2bx zTaFCInT(<~wdy!3?9l_nM!aL1=XeM#QkPIvEV*(1PSo{b!+kmY6g-m=eD!Ppn;f|@ zlNO}F;?fs>)3&ewt`yS%l0<@V=nz7nZUpBefW>($enEAQ-~H?VSz;A9r%!zH--wcN z>c|!~Yd&^xqk10VSWKP!3Gw{NY)GIcA@~y>k9rnr=BQ=B0fe$Zgo*=;YXCl|tElWZ z)SAsHP2s4b?3ly?5*H{cu~UaP+qQMz7ATGOYR0DRtm_biMf}`iQFn=!Vh{tM$OMad zPGk1BwF?%#~& z+%N9GymFu%4GA*Uoz-E*VU6QcJ9Vk3n1Hl1$G7X?R$Gn&C(uJyk;w0$q2sNr!qs#U zodzHf;E8F5t&g(oYu25D1YeLahhknq=Iz`e9oA$AwyphV)k`I_!|u!u(NUK%jkCf& zTjYhg!aM|(O{lrpl@Od@qR99U9yY;hr!5l=p65S(WQ+O(vX|M%)GyLv!L?9$-#LuR z6u2M<|A}g-Aezr+CD)NM3q`umOc5lFTX22@Do;?NGr{3U1s0R*G~O|8Rbn^BPk%zr zaz$me-MMpJ^sIR)?m5-^<)#B_zQHzu@e_b zxsWr2wLnV;Wifq5UBM#1Mrqqa;A0GRic^+o-;r%Zw8(w8&t$gg{l$C)H=G@D6|)Dd zl3Rsu6J$IdtaBjr^YK}6J4~l-OOTS8U3UXRGqlEWQF`gjm+R6<<;<`q4e>?DX+%*6`qgt1b7NJJ&sC z1B&5H$@eUa-`DzTl!QRtMK}trh|@>5Cj#k#Zti?hComXJll=EVSnmq`6cpLyInUeJ z$qVhkj#Z+rYwfg{4IMSvW-a-wf(ko6{9Y_BmJvM8|C^H|m@wJ>U7O|EP374(ak2e^->L zo7c{%f$qll{?RU++$#e*WzGw#okT&EEF`rw$wMX3J$MEjXCl^6$0&5C$X#_5jjqnF zsGvxhSsW4^YYym8upH`d0N`XiH?I17M-hySVkTq0qYi^V0}~lD+Ak!PF+(K1Tfw4t z>ay(@gdRAg8K0=RuBR8$Ym5GTWNKX2~CjAAySONg?k%_GuByqkP-I1^l>o+p?eAFK zg`-aJi9O;KD5HQW@qvOO8#H{pdPZ_>>J+bDJZa6%uC&83N4!1HO34f(=jcLV6xWQs!Fr@M!^D|Ss>}vf&aE34rTj~98#WZ@XR8`c z{{Wd3#2zKps3WQFMLrd_ymED>|JjyEeSjCL3>~vWaY-Tx}gjXk?d`J zeo>Y%YW!TIw=V27^$jKiAA%t9q3Uc!uIyh&fLy0D+}RmW9hrm2@BR53fr5#%o^BzM zg(8)UKDmf|5ToIdIRGN5W*^PP;pE_i3YyFKWI9>F8R|P=xa6kE(zp#(s6&|u8VZMV zyxQIm|M9=e*rQ}RebLM6lY^{3{n+L|@ns2I96j)X&06>=)f3Qkl}$Ed@u!r1eEZw~ zw-gQm7mJ?$HM?*cszHGb9y!rAz4wn2nc&_5qfiwP*g*A;I;bcMAgkxX*)EgSZ1g@t z{DVvj{o-f?f{}CeUX7x~sYbv{=DUcv7dP;cQPecy&=dKLvRlf8B#(OUTy${V1!qyT zs9qI{Xrcbd!I5-8+mBkc|Bl$kWy>-ZsJ|Fs1O+#DfVij|fScMb)N0AXMj=zLFbQCX zX6XJzxwBEqxya-{c;Ez=8Xi87<4z3#XNy|CkTJ+gk9KW299Z_QN*tyQ|B!X0gCj{6 zgvdGjL29jmewx$y%WvW`K~~6k<^v+*h`Uc(`NOvtwR}UyNaTgO&zf=bZ0M*d+OzbB zdMopC_0n;>dgZk1S?CYHXbrWBZhL1l@z|>KtEjRu6BpX3 zadQN?0g7i&xbL5}_%ouCAuzyx7I?_yGv=gZ(z?Pq7jZT@-ZLQ+Nd^MPVAz;xa<)z! z-fWl89g%nyjDaxDtR2KmW-tA`z`^c~uSF`l&J4JjahXP+eaQk6ThF?0fSjYPMXpuS z7FbLI#S~}^_mkKI@p@{{QoBHd`iZtQ%UNCW{8!Y!u>Sr{*-Px~(S7SB1{7MRB*iw| z=oct6r%X;kfg$!Xapp>aGgLuQW~81dkYbatzg>%y5d;c0B^9C1W7`EE&4D;iMU{`{ zD1ejaKBsd70S@*G_9p}iLfxaY>44oriJcK-AV_ok;6^bIpume3=j~1m7IP&Hy?Yum zUO6+1Nlrxj56e{vf-ZgGD{3u5P;=|rZ`%HC1VbK0?I;|U&DTlKlF9TyCRP=9&VH_p zRX#LS3D&5Gs%L-zAYcJBHY9r42I@SDswm#}79E%xF=&72B1qJWUcGm(sXmkT829g7 zvj-2nNLR8Qhc_V#wkQiVMf7ymJpV9a>`d7(#F-=>*6yNhXO1Fv0ol?rF|X!7`Aa$@ z5AS^6*1h@X0*&mmw!os+Sz)oVt%!p4A28A?`wuZ1(*uw>GdT|knBTd1Rf0X~7HMub zwMP!le46z8bIf*&2`rH)K-dLlSlAbFHqZ%7VbA@6+=-!e-w*I+4Io@d%c5;-za@Gy z0a0`h@E@_`o8JF=q*&eBh6J8P{Acc|j-Q+N5G-T9#3(30k$a?}$H4Dk!Ckw2(g&G-1f=RQUZXwbRkN}vuzHaW&2oYNs zp?2p8eXA5LWm6Xvh^m^GQyXGPUb+{-1dJGtK7t8=PAHxj_1Q~4E9dg{um2x%%E>%( zaFflW77&^ofDs248Ueop$nkmZpIR)ad6&)~(LF-BA<_uQAcMg5Fq*2>Y-$pqg2sYV zJ!8Qua$faHY%InCDhm!$Sy{Q%4H0#~Adv;5Zn5#<107b}3$;!-$~Uf_w?2Ibh=$;@ zXD$hD_J<>U6~LA|a4 zy%NcLE)ghS*~Tk!+LFJ_)weM59!GJE0ly;Aq7=3_EA76)EwhZvw4z~!-)9BE@rR=$ zjk>zhp4NZhXtg52=^s`zO#zu>2R^X#C-=Gb0Rq+>&czy64pB0Shy$^9p{D}iLVa?` z0tE*Er2X^_~!RV4{ z@Rxm@6?|e1les~PKLN(VJ)&9&P#igKj=mrIg71gR=hMKx_ z{dd)GEr79bPcbbr*ZgP6`gpsSD;wBqEZc|*r+{J*uW7YL;*4u zAq+8g@?zOZvJxnt9^Cn^=8v@$gkv(@LmXQ6H`jqZ0QHPDb#&i4yKr)!2PpLNb@iOV z&L-DRdpj%n`w$#!T`LxkK>#gDqNfY?IGVB82F)$9HBi?$Luey&{NM)Jo6xV-sfD`? zWaxp4z}CbWE0tLUDAL%QdcX)KrKoLT$7ik)X9eOJ$zomtC9|FEaB6IP{Wh%%PzmR} z-M8&67c9MdLwn!RGZSN#XGS6;mlA)i&#E{O-gbZ@n}uv0Fm1gWq99pf-3L3Zc_}Q2 zT5(XPj;Pgup|uiz;rIADQZ}zUt1Kmf5cYZiPYNnZU%+hign2e@$}*khtYhpZb)IDF zf{&!z==1{iJE+C1YTyWa=Cl7v0UAL4s#pKeP9NDCsU+vJz3%(H-=K5Sfo2JE^&MbU z14hXY!5?7X-MV>2eHf{|r*63Z&UI^oimkGkY&~_97q zg6e4W+3IRDS8rSQlLU*7MGyrSi;Bgn0ko1(p#GV?m*Z56{egV;Vag|n_i)Mc0R%xYN@it}8IAxJ%X;@yeFq{p62)nc zMwD^Ga>=~3ai|ke=JF9Wlf{ZiPn-9mHuUNr{h7-)c)t+DZe=wfnYe4}=oKxkkk3zo7Ys4z0#pymzmCEXTf3^&rmNHIXG=#!48j~A7+7;7V4jRT4`Ci zsLqk-O9F7WKDPWJDM62B(VwB6lGQ=%04gs<{xlR14$-4WkF=Ldic75@&eV`v>p>qn zjqeFZTcUrV_8&c(5|M2WvIBsO{3Ksv$UV?64X`n6)Kt5Dt4>ZdP3qYP%`HxZWYqY1 z61F}diQl*a^y_#|J)$#)x61A=haCyOx z$f5OX26fc=PyB*x#OC+^(f2+~I5JTUWilU@=N?JSari`gRMTu%4o-*wPO@$?8IZ~T z!T4XZWQD~lAyZ%6!)7o2j6fbQf^alzM|~9fu57Nd(XL)FD_ErNxWXx)Ru3Ab&!QR{ zYHLFcU&#J;Yy{hXcM>2+!A?Hr13fNq=lj%oU;sU>X5u`noxDu+%!9jDi8jl<26a@| z(!*sxoCr?2f*oTfEL6YA1KZzr%CMPjBeX%B`C&6_t9Cf=s^-|3=p&8 z#otj@@!0=$QhGbr(+vXfwu+hTh6SOxW^{tfAy;An?;DaE90q z0%Z7EBqRu4p?KY+XNB$B_#Lp2Vyp2A zmd=l)p1}pbQqR@Z%@$uQF=y?}&ttIIZKM8ixKP1}+Sx4>{R4>9i_X_0$`<%LOl}!> zXae}4hPYQpx3sH`bTZzOo0qh_tNWlv66bN&;!mrt;>hkblC{@&`R@$bD*gmKhI%W2 zV6Q&?bqE6LnwuJ|xU@|4T9*lRtquasA(@E?bRjY@2<<2n=%Y=p(Q^;Ged~%;VmWvy z=I8!#!nsefoBaojvRxZrvrFd=+T=OU*{E@I)en-$8q^Xfm!bDhL&F0d0vq1>ny#xe zAR)QkS+Efnm5Z`ATdzLVYPx>**p7&H=;qA*|0fL=vr$5m_ZR~&|2J>!sB6Q>qj1Tq zN3RO&+i!@n&}5f``mCP9JAfe)?7lOhgb{tAU$NO710gTR3@ca0v|~Ht1n}Z-pal~ zk)fv6Nr}7qiJ&r9H0lCN~a5>Uu)Uc03F8|)LG&z8~6%-GRpg}NPD9FQfY4lJg zGJ-h&I5m}3Lv7Qlzn6eZynI|k<8)@RmAljCtfw5>POJ|%HhvBGOsalPL~UKYSe8ge zW@OjD2PfFEY8_Yv;LTt83$k%IH|#Z75XTQWut#4=n8MB|$7?dmJPUA^+PLXYNbrR$ z0(FXx_8fcEfx*(2jp*bMwfa~T`1FpHTYpaU2$0BY*yw3Ce(DNkop*0}!?!jf`w=_n zE|}x%R?Te4h)FhS&a+~b?A!LH3vSAWW!yqmu$ayxwh?=Bd*1gcP6FXv;}iBKf?msB z_)UpQu@5%C_m67Q9#o>W{4*}nk@LK}=BG2)N#1wzB-8!FG?48gRP5?grAAC&U&QMA z^tbAPqm^|d14WRCb;#L*+BS7%2pZu>)J|EVvKHEi)tx(Hd$<1B^>z$_hpac>mW9sp zffmy}J@x5-Z==W0SAd3=CIn|#7f!7{$GO((a^6Eq^Z?f0E_U^v1R+t7t*jnu{rV46 zwv{VCynk2hDu5$F1u~A*^0{7>Zm&B-5q?abr`dDJA&^JQoAEPN*xt==*oi}%JqsvP z7^^EQFJx!kxld4M(6DhfZ{?T8BHOm++eYaRy?rOmd|Krd^cN)%nfnz#ldC6ftA;Yp z4kwA%_?%UPYHS!3)B@AEUOG>$ckXi|8ijU)0v@m@son_zsKmk5neCP1GigxXrpLPOfW?M)jza;E>QO&Jz>CeKYPe+5g1uR;NdRfw#mU|##7+xOlZkj_To$ZF zSz026ybwJi;_t*qST`>-%cF(P~*k*ii(S+=s3W{~`Lx}+by<;pf-*R} zWbj=Zj7F*FvIhelQ1^%vEfEp7hkExNAR!yt0|2&ZjX~6$41QFjmdK1I!3rz~L`sH_ znIW}LWbs1}z?kNx1=kM2F1v9LRMxJV{uC88;Yd3C)<&Qt`NbLofTFXC07dA+2-@_k z9xjl0>&9g}d3dv020%k)v$;NH84ja&%E?y1?m$!v6;po0#^qe*VZ~kRZ3L|6hPHP1dqBh0>e->u}_>c2-ra195if#ZkMtV0$Zul ziL4Kj-7CsEYYJc&+k}}0xgJEN4+T0bNx3kB0OMMl+f!Rwxr!u3xTi>wL$9Bd5Je$q* z9WD7LDIn(!7TxY-tO=S88$HwdRS(tqbNc8uF}&J(bqy?Yr zG0$Q98G2hf1ebCbhL4`n0${^Iw^iDz?e9pA&t~HT89k&H;-!3ET_W zm#ddgs|^9|MmDbc2Z7NAPyUi>A$F|)u4+S2{-Q7)!-VrZKy@(NZCK5Ws9`YCEwX-O zR8te9AKHsG=N@nYh?W*PeH?=4j_(veO}Z)FnpxECCbEO=t%V$!54S$T!4qGP0~Cjj zb-{Ds$g1ey%b^Fbt(ryJx+Lo^+PRmm98v8(W=DU|oB@>8Pmq8|A`_F#tt09TjT>4O zJp@s(#1S}mVwasdyj5*oTy(lgnRaq_j~+EBAcB}pS$SV&%u!7Z?J>g2YekccvQhpW zfp*%24JkD!Z^LV6Sw+PFJ9A>EojSBh^dFar3at&A5ps&enm7V+*~TzNe_K zA_9P7Cg8TPq}0kJ8r4I4ka`c-JJC5C0U$w1Mx12K5edRNf9eYnQ8>jsqzLVfWpZ+#=?(?c?gUNE@ z(57g8xd24kY7)Sq4vta-m?$t`2oh475ocfIlKT&~1?!Tt(fMaeUd7Eyi&P+2e)9KJ ze~EhY>ev6&E}uIp&4Hk3-m!1|IKMj!SWKQtsatnvOiYC?mhA$}02Ha+rk^i#O=`bY z>QGcHL7P*DHVZ`hjo|*w5=hI%w@UdxQ4r9qyw3o8<}?36;yKi{eel*_tM!WWQPTcT zdd1}S%YtnTLAsC>bauoo>K1FV;v$~0#L9a05kso7dYD)|h~w}+SRLpca5mh$dQJf( z%067pvOD(~AJw53!V+`$q$GfZZRXglrJvK-5lC0B(j?$?(cWMUI=#q}dz?(*xT(u* z%G~Ge(5_XsfBW0AZ}Xn`l7KLRH=)OC6ktoOmna(Mr`R#!a(iUy(>bV<_p0b;qsGp) zp1sQL){QH6_QVbaJX0Ckj3@3iSQJx&dU5BsM(4$2u-NG}^)Ky%&L48UKQsN}0)a(} z;7dy7U}6}4l3+1&@H4?<(qu%7J+VW>17ri8^hhK#aQnt(4?6vUpgu}DjA{b31m!BI zMYP`N(W_jWT9IU_vXR9o5C!Gn&iB+WXwcAcws-5BcJBBt(dnQZU=ZQv&t3L;WgNGy z|F%_B4pQVA6-X!`75xUwXm0=DJ9hEZeg_s4PF`nCXVMA7AP2#c3#ax|Sec?0cRN_@ zhMkoya>Y78$cDq4mKQ|m02KfR*MK{dCgxO6^L>5Xz@mSk+?lI{li_$)Eox1Hh|8FX zi?mkB=F!U&8WkDv5R3@M0C{$r1Otu~{J3<&Zqz|NZSX2>&gD#vV^*N(vUy0!<2ciL z0=m!4E}kf+`-sDp~oGp1o}7$jLT({5;XCP9EB%tUbULrDU3&!zQ4v3fXru zS{!~jGhCZ`7b5#^7~Q9kM&Qh;UN=2@WPJw=wS`apijA4L z*cu_X9 zUyW(psQ_}~E`CDepRX}cDx~!08TE3ck2EyR_kQq4P6Q>?`)57RGO~Hu1}`&F;Dc+9 z;o-7-P6W`Yc4FtSzfSaTu!3)ZNBSNk4p?7*$8KD8{VQ)>yJ!y|QhV6qT5@X~KUO%lp{g{T@ zd2{wt`ed*PO15Q$MhZrboh7iCjJC(r^msMrKJYqLv)CS3jBIztjmELCU}`cV>E zefWK=nXo`DK~5jrp+02er#)e{lNQ^)9d9eLyX3jAs97+M*zlU^cJJ;rwa>U&cdnbj zVw{)LtP~c>0mpdI3Lsg>6u@Y%dF?D%&A!HCs#QLFAly@+6|y{W-f-*~e`sU3Z`Ucq zqds|w8m%aEl;w-M_nGo}l8(P8d%aVt6M1w|?OGIX%lg>l+0WRZk@Qu(VP}r-R0|pu z{>UZ*l!EFcv_m4sL|LiNqvnAELnNZ#z!7Q#bN%W$*YYJNMXcj<-`*$k&MdZfq2M25BZ`Wp zE)6S!8dnDR=GC)OOGL!u`2G)7#}veG9M#*^?1jKXK#eHL0!~n>Ms*f7(IDg?$ILs~ z!AfZzB^{ZcV1_Y(#VD)jd%aRK3zLMNtuR1XGftQy&M3O);15+VTDegKY%&GHUu!T?mnw6IJu;T|d*!nmB%C`szwj|*S z{9HJ7ZGgq3-yHU91e(HT@apdY!1*yj=@#KHYEhvNru_RH0m)o2k#A}hvR41We)inw z{<94qJ4-6M@Bi>m?9k44eRRJt5*7=Z2AS7y9dK_e1d(`m7y~c%6{wQ|NJ8(2x=9wj zdT@;)G6zkSwn_x+V65Dt701={cK-BU*>{*+fr?H4+Cf7n*y3k@O|{RP-~T7C0_sP> z8}D=uuN(YH{DqPpHfzbJZ0M+|wr%aVr3v>kIze$J_WmP??6OL-|3001BWNkl9^d5@4I5p}XUHJvIednU5hwdaoelsIXNLRd_tZp?kz8*3+sqSdZH`MF71>nU@dRn`TYu6~LVg38Pw zcFfhxwG^VjSw42ti?EX<08jeR!+A^ZozF_pf$h zGO~?9;WCTA)oHMp9K@6uPH3CvMU~WkrH4fS@QwOckCMIb(Yr#b+q@{hxn6fh;L+LA zTgo<0objZ@{%E;#c+XnDSJGfHb1qwZe(hyYGm;uD2*g#|yeEFadiE^0Eo;B2Iiw}d zg;RTN_vY7Kf6OFZKO1#FZ|O!)YfkXCSbjarTo4sj)PwtX?99<^I+xlKMoRgk`LLrB z>sZ2#WQipL_c34#{9FW~+O;%4S8s5cMYnufWfp5DED%@>4tK62E+<&@4nSu|tjl0g z5#MG}MmVmCcKI-{yQRdTkzW?A#mdU7)EkZrNW}j(6O{qgyV|MC?C`Gl?AU=1C2B*B z&aMrw+Ql;mZTTnuwe_hQYTMU;TVRl$ZAi#Ng%~how6c#l7i1+6(4awZF8WeO#xxDe zoS^_zL6yCH?wH-aap7kYEP50zx@2JyQuP%wxTswc6u_~~?9-UvJa=Stf3ojwD{Jq) zRY#!=Ku4`&O4ZkG{M6;@p@rhHd8lU!LfSn7>Ed-b)3hI@AT z>|w7^`pDJzs>Z}Q*0KX$bcw%H(-YK-<#6Lj^{$k1AFVMEu%THyzyc@11wUMk2N7|E zYHFu0RdeuLSI^n8eIF=NuO5#671b^m7Ksu{fB-NzX!r#6A8TrCRM3NZMkurNMWZfj z!n75lj9)x`&`uxTVh?GfBDGh?21wQX_%VdGJ7mOU0YM_;PN_363#z3C$~EXm2e5S% zRR&V<`5us z|L%2t4u^*}C(wcE%Lcukx^~nwT~AXe&^<-ttew0>8M=eJ-V;c1t!_%>>^3#hHi#BP zxwuzxu%{b_FLenwLM_(Zih@wu=L^ZovKxS*OlWpeH89hG3-hoN+)TjQP4IeX0LD6+T z{;KWY@vgN{Ug3qL*gqlA5`+Mg-EI3UB?g4$n&A+Ru-{Vtz*cWAv^})_U^R3Pz2a*Mc)CdH&917C#1H5!ww=aiTZS*;>(? z5>M=+@`)iy^#F8KR_dvc(;hNnq70(*A`6toLX2kOtfxik*}CSNHfr2#8$aVoMQ(R* zcum>E+R2OU(4N(HaK|bcsZrzR$O+?n0ik3mQ9C=bXN_o-A=(|hi~LMfdWB_X@c5ZA z!68O~K~16)oA;y4vSkCZ*$%s8{4jZcICnVrElspsXcT}SHgc-fKe(;hi8MW{twSZi zfsfDb%*)mHQBMaJq1cqz&=FH4*}vzBJs#6Xt=-1$)~C{$z>fgnVn z9@M+67)ryg_Rayi)>(Epa|Ot)OZ=hIH?l9VzSYBZ5LWaXWcP00kbn|%(b)7*{V@am z5IPVJIkh5W)vsPWX(tYC6i@_Agr1LlPoOrs`*xYlV)b6_p&oIAhfffIWS?`t06j90 z&?qmS*{{r_vV&Hj%$P4;Y1MNIrwl;Ur)r2@CsX$37IoKTO}4H3 zj-2A@3qGlK7Z*o`z9MLFW8dErnI>JqX?4GD|pPLg*LKwj$J-~ zSXqzzcW?PjgS*ed!V-Jb_&|Y|!h&M!*}KAq*UXUc8G!h}&Q+qUhRkwI9}l~zGgdtN z3}%*KMDI#w&wOAAmcg>;f6IFHsj@Riw%fWl|57z(j=G&}sgi|;`qOeMyK&#-d#Rju zHvyV>Pp{tntZKk;?e)NB$+>p({c`_4N&+U#c*2%_;$O?AAO!W+KmWenrNqLEfw{~g ztv`Z|Y261i2^RAMirheJu$Wp`dW%1~eFil7duNWEl0A$nKx1Xq5bIshUyKa`YLq|_ z#BZp-Z-;lkr@aP?N&+`94G1PC+J$))vUFCgGnL^jCV;=-sb5y66W?sslFukexqZW{ zcJEeQDv8kQx#NGxE8x>=ElHre$cB$a1$DSJH8t3&BimJnpRbleM3?W#p3JPF?cjRs z^4oJULw?%#)#V3!d;$45BgW2BK}I<2^2;oy2QS|ZkZs62msw2159kp9MyLeH9I%_z($UpC1-QX+HY7%aSxlh z_)}JY_m*vX{~uMzjk85$ZTtG~sD5YW!dK+P^4(DEP9EN3$E6Z^T`H}Jc629rQ*Nla zSyWe)-Eg8+RIN?x0f2LH+t~$CbywGROG42t+xm*5=P|o3b3Bl$r>QcTsQP<1Y{1ZQ zD!!*a4^gJ@Y72aIpZnI4;b?md^8$;iO?15pX$>=e+AkpCk=h?Ltk%w*qK*<(zziXvjx3KH?{yAh0vNVIug>f1qWU1WvwBzd zwsz+z{eQ5sUKO_Z*?(nM&K_dde5dGsehTMP-I4YU87q|S(?3PqkaVkRd?B{!Yk{ewhb1&@~NC{M2#{Sj;}Z z;Y@QNSm)Q^F}D20-%+Oj&Ye12^ZK7DC>aOS(&HJ%BQ~D-jdxz_?PLC?e83{}T0vWh z%4!AIU^YO*c1tr$dzubCbAhh=Kr*#G{h+tr2T?>vf^#qo{iVr$sCr~3L=nne=TS0b>G6Ja&>7miYKQXDX^( z;3#g79^O-QIO$-2*!+W=F(KEjyr*+GkZ;BpALs}wk2t`17I&*BNsFd7? z;|B+Kr+elh0*lqd<*Wm!>9mbwIH(c2r2F z69=6dRchL3o{VZ-XlIZFo~_n(KD3VTAc?4I5P!;N%+li!3$f(dW38i-aa)IQE!HFy zxr#mmR3A99c9t@8G;F?f=72qTa8L9(=t6-mit|fNAK5dqVD!FYv0c7!)UIA~nIB$q z7zK9PcFkQcRI|auC#p3CSweyk#}96hBR~&R_6YTbyq7u+qPqZ$iaym6fjW6`v(?w% za=h|Z?FR|)Dqm^}%!|mV0^@yMYkZ3Cr#yvkLpuJtKq72maE9b0gz%X0-{BMeOx^3OJ6kO0)s`qKJ z=8|jy^FZw@&JYj`pbjmcx<5YS)|U@VMVaD|>2`l6>o8M~*1PF9v!_p ztaCEaljb}l$Cd`+m(HWk7(U_dDS)d`LtD|Ozt|*vmVSz-k8IZ&A!>N5769EvKy7=i z1iQigV%vL{_fs#s=?h-c)9>2+L)-Z7-^aa0-H2yb-2Q1hneA_jkL(>Gm>lYyEBg;q zRvi&AweiXV6f@6-d|(*#?1{6UvZc>{MLq&*>Z^Y6N3vs5k5fS$1nddc-@SQRbkyNvXV`;#x9s$BrvNWqiJs;1LLS!Nll{DT z?SjrS*difd69-=$+a*;-5ZE$)Fj|kbYvTdCi-0C)9rcU&go; z6&(e&dYFPz*iJMA&Y#{dyOPZX>FhU0&(T@BXGg(kd%N&4SZr^Eex`q4Fnr96mM$;W zk9Y_&!6I2cGI#tZ#~^V($sA-bwILdeLss5*fDIWwQM4Uo{o&bT#O~d@VddpjHfQRkF2amG)J2+Dt z#FvNmMno>u!?*(={(o18GaPtu=85bf`Vl#19mp((vFncY(V9xtdS-ZT6fx<$=K!D= zmi^=R{ive?grP=WzkJ$Bng@p{*LZdUEJB5JK*9HJ>_A{8%tJ)0%rdd9Mj@h{ zrZaBLB@{T+-fK-AcWb|lsf0CYK_iw2djsH*#76rDnht<^1wXsu{XdbEMy?XJu znmlVN3tdy__{Del*-L@+1iiDMKy|8&!N6e??9PqLcKXgoruogQax)W}UJJD1=HVN7(~E-=1=o3=D*9a%%Ka z*~Rw9HEr+XaSB;M1rQ61ZJA05Q20Ht z<8Ad*bV5CuukN(sIiA})WJ$1yog|C1?1kSFBtleSd z+n=kC`#Vx#5kas4BLvP6*h-CM8})7Ng2k2=>)mI7J@>i)Bmufd4~c-u+QyLisJ$<*XM713Iw45Xz=H2vBsi)}>hTnWf&@Z#d94Fux6D_3?DsR6jXxVXk9>u&2>n0 zdFOQnEXpi&6QkfUSj>A*{VcxmXBsSWNIG!Q!yZ1kqekPYx|k@oo!AT#5+uS?Bu8h! zuyM+gP!C6~z~u|a?B4Bb`Xu#=VC!P=+s_r=k6k9K#$@VzO{hv9yL-eU+ ztwsKBO>3Cfm4%)a9BBaD9k~n^VlHvx^Jw;bFDTy2K?Jx*eep)!8I5hbHJKgt=yj-9 zY0gj=EhJ!I&3QJo_8E?-$7c?MEZV3SNbz+=u2l<^M>2&yY{1YlHfAE3u8~?xG@7Re z-lIqLKFS=^6?qkdYT~c;whZN$IP%%+8+gWaOXP$we;>{y*E63puHM5#EwB@5;z3s z0MN_71K`F_TVX?nPqM3ZC++xwjdttWc~Q3LuUb85jCw3`uVfYpAkc2(X5IOy7g%!L zvbX7L5r3%$9IW+p+1>aL!_{Zjbq+jZR`a(jjm29wsFa4bVe|vl}0BFP11Rj zqA6LL!a}W!2{Ts8i92^{uN~dH&IP0bg*ec3)lauc`;Y9&u+h^cpagZAbwJ&EU>dZ( zy)L_b9e85T)o5v!pxTO;ep_NwcW+;}4e$P~TAsj0h&n~IOX>Y6@4W+$`4PWWtQ;Q{ zf%;xmJ<=K*A1DZ=M)Ij_RPyHH@oSsn>H>N6Twe0rZzyX?Fzwy%{lB7Ty6x+m-KP-D zPj7x4fHu`N0|E)0Ok40tdvN!b)m?Hyz}wd^*u#hQDit7zJ89;VvdshitI`&)5o53N_kajsoCt#gjxKX!!DlTfpr6)Yyfj@lvh6lHw$ zgn42)@Ogxu5a`Obce^sOnORp3%#t3xZ0w}PR@S@1?%lm?Tn95!-~v zU*|E(&unHf}HW z1;=^nQ>BeRV$3Y5eengC&mR*d5Xb8D@$Jew4jM6Dj{C!h_a(;C+|VHKc>d(xNQ&N{ z1d-5ys}t*rsmi{Ld1?+MD1*@CE}lE&sfKD&=Y@sDF@ha62yt z*b7wb&%Lv*qGr6|v;J8eNaA)|)Xxur7q+H)-KWH89}8nlNZ^@v2#>cdT94*H6ni0a9=_Z06wUU2p-(Of7A7KO!RV$ z#vxh(Edps!oybx`JHCDMl7J%hFHV@tfmOzdK8ySvV6R?ajgRcy$vt-Y{2`4QbH~eN z2uxyD)btVz0Q?d4X1wU3Sk-@oEqvxzlo36!W0isvy?ghy>(|by*3H$m#p^heM%!8N z80vwdOLrA41`t$GAhyHO=f9$07Ij2BH@s@w*8j6aYaG?9Ky>A~%fG1l)@^IPC3RiK zl(h@kFYVFOMo(O1VQ}n!5!~PK!wa5GWyW31`Ms0eeG3VsX8zE$|8tUcj1IG z38HYyDfd*-uvgm!i|No>wk;TEd1DG+QAw$d7&}`%aLHWk+V}&B^RTy*)*{fMrSjU` zES2l2^FErB>U&hjs+ZXWR``htG=&fjSd1bdJ@ z1Cu#=KdF0f&r*K8ejkBF#E?pR2rQCahaM`hsOiXFuNY37oG!5!Swe~T`7iue8#SJQ z@n%Ih+qyJzok*AIgN%ZbkV6mXk`cw_J znsIY=c5#-RJw_Q&qPUjIeU*k){znT8OtojFoI2wp+SkuDJwz~bO0~B zd~V10C3F8?R?$xa9b^@GKT*S**Dl%3y0fnKODzXH{mmZ=q1Tcm{0EE>5F?UKYk`)= zMtellaVxNfM-S{~-8s8@<&@M?iK;<`iwde$F6j@Ps05)qj{s*#d2Spb9B7=gE9VjM zXjZLdn_wzq<$Tm&F&NEkV9~iu>AFXL27oY+L@Xm}W3I8y1s1c>Ffu4<0^m58%wHa~ zjQ|!ANn*V~$#YJIn*#SFt=$S`aUL~T&+>jYcG4mnRx?#=l7p9eFw`e;z{4xZWjpZ| zQ}Bd!3dN8^{K|!+a`+#ihU@ENW7pHImCVCREi@2g>RoBIQsJU5p6Tt zXDuyKN39t*N3A)?%+VTyb{c>T?jI2+oNgk|2&QQ7J*ro|BlT_0$&WLv&1CEG;3(yu%ED7R5fkapkP&rGWeyi(Zy^($NDSDl&ZM<`vb}WXq6s7A$7g zXohvJrIA^?mrr)li)T%y=^#^@heL$NUT^kJ_s0nqk zA=5~$@8nreTc3VIwC+zG*&@0i4sPxm|1P_IS8EE|mj!?jpmSbG>LH%t7oLJvb ztI1@_Pm2Pj35JI`Mf*ih|Eg%9_wU}cecOJl@*j6z1fjp~8QTC>1?FLk5u_gp&33HL z)(a>1+O@hfv0s^Wk#x}qd<+)b-FlDT(Df1cnE{JgBRG8rD#Jk$HNLkKwMf>vxpgs2(!b%KKEwF~#YGDh0&|BNx|nL??1I!Z=Jl%KBKZ-Y5a~P;s}E9~&Fh487^m zBhlS(CS5~xCn%G8MfE1`U%O}`QkPD^Xu1D5LZc@v5Cse;yQr9qQY@O0KMl3(i!6DC zB$U^`M-Fi2XvI!h>?Ec~EdVl!5-CfS3Ou%*S&RT*Th5>VW`ENuneP}WWp#3+dsZD` zk<028y1K4RuozlmxDjYk%aifbpD^g0NR1!ew^q^7sHa=B#uGJtP-ZKu6;18ktJ3Np z+_CGIPD!XqwR=HGDb$T6R$vO8YabO$3Z0DR@S5qO_(CBfJINga0At}8S4%iy=9AiA zM1#5CTi35xL4gCOG)HPkv>{$s2WN zRp-gRhk6Qi3P2xd&}3|;%zIuxZ(aK>y+0ZB$)r>Ml=Cw}FXv9~bt=!yg=&dhu+BM92y_%`4*FIPwWafO7UtuH0 z&QbdiGUU{svLEpO=gLS0uJpz>7poB@aKah|*P zwD{<+7J)_VaCw#W8#q#wb^uHIyz1P&5!`(Cv;WyfjGZOM%KA6|LMp-mh(Nuo_^|_l;cm)Gv!YvT4oN#lpZCVFzl) z&$VguUbG{7*V(?UZk^Ji#<3~zzpx*!7b?_M0<8c(gvKiR4U|pC{$IUvTBRr0YXUfw z9k_%ecBfE1W9e@VJ)6wu?v1Z0Fy+i+ynnl6Y(v&nf$G9SB`*NRz02ukTrW{K){gVN zvWIKByz?G|#m+A6$DixK2>eWf#n9@4$Q$DuCEaYE^~weVy9jPhO7`IK`+KZM9eEh%5kQ(ftS_~&Q52kXdRe8cYY=5a2^Dp zN;zUIj{bQS=V#u_PYW!@qZ`jp=DlRgAjU8;QS(H;l-i<_9?BXtJiMDh*lL4@nh*}j zWvpHFo(AzHI`E+GrCv!2ZAP{+%n611K@7vQPFsOR(cZ|u6_q#StxkP&byFf|??KXsWhQ7E30g>jT24=9y2a@1G8(|vz|=Bucr zMD>+qx(N8x-@D}jS%K=`#!Xo&r-5e1M6$_l1_es8S3^fmvY|E8t)!$>Ad#9(gcg)F zDlWDn-=7mo>fqtyC9D8-ocp_Y=74C0{2jU>0#rBHCw^ZO>7KLnb86nc>HV*ZDG&g6 z@=xu*MC*){5JMgtIcH|E*@Lb;t`Rx0{$8T_RiwMbW-a=Z&0hX_wY;D=;QF`!Mykw# z3aa(tg=<(NlV?Ax8r9vKUl)y@Uqh`z7za8upQT+&Xjv2Lh$3cyvYXENL-Ce5Lme7N z8NgUIu*RyYhl}QS|MoS3MVvqCl~jBF@PV%nOP2X$r>AEQPl)uZwz90;rp)_<4I44p zE?+p}K%X-6uDz0K8g-v8E1(t>5=@$76K6gt>f!!vZ`qA&7koydy~*gZ+t=O~xZkTT ztA|v$=?4l$ni|ZtZ+umtRyEHVl*x#S`WP&>ImQ7j@+NF4V3F*))XUvw&slqx&*Y7p zy4;@n^uJfjtt%Igs;?s1GFSHE&hjD;JU*h;)b4F3{fpWu%WcMjmu&lo-?bA5Hb{() z^;U?obu)dWmub%(*}GPKrbBxS${(QlFIf4Ds%_l3>T7B@hAJ^9DZ8f<9*I%!@?AUzi|wxA$8YHR z2>gtI#aP7+#~px#8cA7IH1_vB%la2lfI0pqIG|PWR@<_ zI-{Z1FMV`M(LbkzsCr2`+g;xJ9iG)RSadJ|@PHGHvg?C;w_BI*Ij^I`-_>0oNSf`; zyT}BKxxUjK>@6ye$H@b15S0|AEqb;@CLn24^8t&fu9o&xgJGh;WKmR4p~mmtaq!Mt zP}ud}T%zR61u^1`Vln~h9AITMni{Qo2z1J4tp9*f%I1;1Av5S|B-5kBXQ=%O?J)pX zPPF8nT{(ByWfU9kX?$Fuz&XUp>}U{j2w;)D_5ZW?9#DQ=*Lm-rUI0wN02mB_LB|Yw zF9gv+f?cFUk!p4%xyy;8II)xX<-N7uTW_rwdnK{s5-W}(xk{E~ixMSLtRM-HMDJzL zdoP3DfhlkOzH`p~-+!5oMrme=A~^V$d(S;(fBXCPw+9RvXQL)8w4S9EVwHApdEZO0 zLR$f6gu-W44IXbJ$IlU?c>KT?^$wLB*n>g^zVh#C?fU2cm(qToGmey3IHHtx5R?pvBst*)zeWMgXt48 z^g?=eQlEI{u#6>69Nyu9wKG@ZIZvDSvLwChKl*{4JXDu#43uKj(%HmNDp(Bv9iB-% zI1NdamVyr5x2C)AY1rIkqo*vfIZu4mdi3g}fOpl>zn7yYfJ{IxCWj6^H)|&@w2|ZI z+pbMZWu}D5)3~Wm3Bd2!{-GV-z1D8tq$aK@GV5~l%k3!&_0?c}lDQbbU5Dv%S^C%L^heb)+-0=F~s{RFWv4JQBd7(?va~pEM1St`pO=IZJ*; ztlp~k{$2($D#^(*l?A~n(preb1-0@)3eWyXNx+yXk85vVyX?Dm;?VYtU@`1puGNG; zw>*IES<+W?zM|h?wS^)f#3-Q>BjJQOPS0L_tY-2e0ZEcQ^`{RxFq@%#q^n8u5UX$| zvA^{nG)CtaPaNYf#vrw=SLzeJ8&5g(v`vaj+L}6T)`++D0V#jq(&vTs(vI?-4t`_z z%kSd|d?LVN0EIZ(W#weqts72OC*8U)%}FEpo1AMO0eDI8N^MF=MUkCetUs#4@^ApP?&gCBFM@-=Q7<(CMm_;z2^j2 zYKz0|Dl5nOSJx_t0GI;yIA|~h0dP5)U#zB!Rv8VqW!8jL6UH3Na^^ILIPd3~tAVs0 zSE3=hYntq?F9h|jRxsO!jGAgA#>}yz9wlPl=p%|mlx!_y3Xmh)TUgY?DhH2IYl*^w zV)c+hB8sVv#-BC7>r=oY*=6_Rn1Aj`ih%4~v0g~MX^T-k9Ja7P{YZ}=+#&~JwK&Mm zwxXgEB|)gw;=f^3U=(2pb0zbQ_a=jR_NoBSa3X&tOO2tzz@Zal=z>fL1}!)tlSBfb zAekCDZmw-z^%Fa=Yju))vDTuiU<@sIw55~g%yywFJ6maG0qofWlP3P zJsZYABoPQqH-G#i^+eP)`)>`Or{`fN*IU>{7)08Wj2b)7sz*$+lSg+cfq{e+MlQMj znmOd3ZLHQZ+8MZ&EC(6^W`IV%mw=r5B-m`~OheM=%EeRap^B{eT>VjNqHm*5&iTdN zVy=t84VInO9w^hct$$OsyHcP4T(flva;kLNiR&=*fiX}ZmU1|uB42v4M@C8||?>!1HnY`QB? zNF-U*UC_(A@9xRkkx@^d@gyjTqo&PyS@Qnv8{SqMF-mbTlA%o#ZFkO{Ib@6pD(TeZTl2V$H8Iw)OBVB=lOvS^Y&y(guk!xZpBS&A zDk=-&S+TEBXH1fab5VPBlDSRdgVSezIs@6#$OR<>=VvZXu_LBv&QObw3+fFL^|8cs zrqB7gS$W-Hu_FuY6ZhIr3|M3_A|aE+EH6))aWdtRsZH2le3p)&yKmJ9Su|tS3^PH7 zkSsHsi4XIlxWk1xiT{s3$uuzf)5wVD_r++j~fMQ2a(=!4FuCi_iwSo zd)LZ_pI%o1Sg`gOi-E%?2q*$Z5ARv84DrnyS9B(zXV$ur$o2PVt0sgn2lXGB70 zK=oJ~IDE1sNc-w&&#^@yhtVXcFDmLKSJr+5Mri#XJG50bDY%>l@aY1LME1s=)5(WF zzw28yOzk$1x%Tcm$npz%N_L1jm1Aa)*^rS_)K7J9-N&|j%Li%B=Pf0MQl+SwWU9I< zZ=?}1d`X5j>4}^qW-*N+a&lii18cHA{f63tXMbCOk?+UNbItqTv1?b(`QdS{HmRxv zMvB@*dc|S{gQR)zsHt}0%rV=wnrn?W{q*A78It{u#bI)TvS< zTGqE(tO15YH2J1E`IQSNRbz=98n#huIJ9f=Moi)3VcD_YFRvIVcTm_=dMP?{8mA)R zl3e*flW$m$T-o){95H^L4X>GLM-OhXJzJLBwX5e-0CoJCB%pR{VP|I|f{+|_^^vYI zdH8|xoH+A2o4)9as;xu{_`&Pn(7EQ^wcT9Lv?sT|uioulyfb%xFW=MtQ^nPgH>)ov z2?S)Q5m=0E!W{vN0MA7)eBFkQnjxl%wlr%$_^xwv_WQD)Tmy@1YXTjpbbj&&# zO_PLz1p+c0>KW@#9aKQA8WCO_H!})AGY%B76rc%vd8G{=Io+xO z71pfa`sCp{wUU5sk;`RPmfdN%Z3X#7Hf+pn)wAIacyP~JxraJH2l%BW1x#UJ5FJ2F z28{`zDz>tzQOqqaoz){JTSG&G9o)Uz4)0zkRwtO%@ceM%#3bSRm5a82*Gd^rIJaSE z9*_W|anSFjnX$EwLII;I0t&zotZd(bBh_jqFE`&VUpgxZE`Vah*ts&qLCzEp7~2Ah zF8+%%kDl#TfRm@blibtI>z6csP9>3G6vO;W4l3L{O#~>3AO~X_vhI8iS@l_uec47& zUL=_^tnaFK|5g&MXfKVM(Zt{dBS(^L`n;EAl7xJhG1|WNXLj=FPK`BSUc97lw~?4$ zv4lo+;c@0P!En3X*Y7Ic!Ik-d18=X=N-HPmE334gWqrgZGpEm;J}9{`^Bhw#nCnP# zt2!r)lX}{?=}%c@^=Ppk@qUW&+FaIkQxmm|FdoRS$IGM%LyjFA-*I({s)Khw?povH z9shmUKe{gLkM=%&T>y)T?}iOu@Tq@keXB;w9dh{_|4a3}!Nof84RYo9=&{G;VO`Q?IVzNY<}`TOQS{h?ZQ z1>b`-HZ7D6+>4=T*Jq}J#mF*QNj~Jc)T&qXAEug1lqjeX=>5BT=|6}uMeU=SfA%}I zV45p1iL`ykrgzoyD%8M7ds?`*RCZCUl|QNd-;qEJFT?2_6%foPqyl>?=LC+|iQM7c z1dFlxr0d905*39+b8~~tzmUZyq_1v$-JN86@?O-g$Jza&?h)wX2xL_cpWHruMi;-R z^KW;{O949#$BRo8z!0p)`yM${i+rmbRAasSR7>7KFoVelw)q6qiGw%_Q<5&LC9s%! z?Fmqj2ogGfe|PttTpMG7kwjr3a>AXKo#TqnGi9AyIzm&&;(mg~j*N(#8!o8hut3st z=T2zF;2hi%#xP`zGs#5LS%N5Z!c0QF7AeAKj=A1!NN++AnHFZXAji;HH#G}XQP(kg z(qij3aFm=3$<6}OhK-&nIV81oQB5IoQW%CTlPne1c*w}!y{;0Ng-S$SG` z3>Z32?JIU|eow)Oljy=0X%_ftlb(x@|2@G3Y%Bl>fX%hyrdL>8DreRHgK8y1Bp^cC zirk5Y(%aU&o~T=j0l~DrA(jn~14@F4P?tnd0egpe4l>GqY>HJ6FY z^5Ihybdt@VI`>7JGUp{LE-q2M&a&74QnI&rax8Vux;f(hzqDeY%~Tr<^vre3{Q5dNn@TNHP?AIkonH__SY&4)$~QtIPiFkuS_X?h z@31iQ6Y2n1^h%+M${|XQTslYHncru;a-pb4xzq^&C7d?nTyE+&F^3nw@ULz7=-Enu z(I9^Hdw(w$Jk$wC*Bo054~|s~CtG49)7Gx!(3NsrA2fWjz%+>-02*zcF4Z5mTeokh zOoG~EST~qj+A6JI{sWDfGhy<{q_~u~U3Im|V9iO?-F2&e(EmB%0N-+$+v2_yt@%t( zA{k6m-Y{g;OttNx9u+l%b5M@@c(tfp>qxwlfSa+zTYO(>NebGrFX?`D_Xwnoz(Wca z6Pc6L>~qgvy%or*?nX_>U0n}yGNe~%*r`Lhb@RH_pWbihPPwdLFrRUI$U}~gyEswV zAOX!}_D&J__O@3@(rmn7I$a`z#ST%hXbsvVvyBNS||nwCUNKHckE*Q34I50P=a#T z0Nlyu63&fHlK#Me!5lNMaXm%OLtP(5{LWw`)G8+6hCU-EKP59xJ>Kv!k7#XR`h;sP zz3|SQJP-jFdP^b^1SHaE9X9UZ?zML1;%UE>d=TY|M}4ooTmd-(+Wh=NtE?U)EAasA zR5zAG#yQt|_Ufx(9hT?d?sak}*c1B#MAEKrv3Ss=adyM13@o1>*vX95SdAjvd^hX6It)+lb&Y*DrdBD0PIxCMdu{ zCQq`9apIrrSI?`5<=Nx=?DECauD&jV@*&gC75Y;GNU3{$WbrS{KAt^t<=cNPH`_b7 z;;LRX{G`v>&~=lR0RT>v2{`)guUip0>#Ba17DY;6c=HMWk*>8!ST}B;bqSB~YiF>O zyn5W5gH&3stbvUtQIVaax>%SAoCf<>yJTQiPOhE@y*%mJc)tFql~)XsJeq!)yEZPh zV+XfNM(q+B&Mbo@4|S{nT=oN8d`Xz}9Wc@k?OrQa-N?YIGy8CB^=oa-(-?yp_NFiv z$bH96e^M@wFvmysZIp=!HOj%XCpMCux$-W&r=|1s!NQ&78*1eY3(qBbc5Ys?53mv$N2Pq}x47mk`R#`Pl$_vaTheYy(|fvhfvKMX=-EpMje1JX_oID*I^+jS7aF_&?dTPG1r288iv8vi?hdsB0xWoP9I zykoopNTW|Dtna?Mj|3E{bKr0->pMuY+Dqq8=*vSZ2Us@dK24&T=luTcse|fMCmCp{ z1@rAh+`ZGU(8-6$wg#rl)ozhcsI`eRp4CB@lUFDSD{RuqL)&Eva-sgHA;qd0KVR1i z+j(I3TGjT2-lZA^Und;u&ycPLJ9M(ilV-nQmDRO|R44#O_Y9g<>qr2#zwTqny=0}1 zkxtVc^*I|key%_@wTb(7tPraNkaF&oz70rfW;HyFs0PqMnBtNOwfcZ5;2si8Y?hu; z7;h2>WW%Wq%gZmYotu{`I9E}u%0Jsa>=U5T)r&GF{RY<9n8}M(v(wz@SnlJ8wpekm z3iXl%gk8B*Zzm3IQ@ar4)EK+O6%h_uc}bRc8dXE=<|eBiHp%8b{Tq^o-MM+q)_wQ` z_1&YLh>N{ap*m z9IHlHkJ1XQo2!@4DdE$jXSw=E?%BHBu3SDV$6z@m=fGCFbuIwg)F`R<$O-eb9&z2> zx#>N-dHteG(A=#}I+ZbL<8$4!j_s(v(Kl@O!cYB6tEwKWv+v`#z9q@Hq|u&PchB(t z@5U{|u={^4?Ewc#$>Nx?4DV$PvQM#ANEThYRBt!@oM7Gn_>e3!*G?X()7nT@8YQ?N z=07slB`^KHSViXP#+5&^bsv1!Zr!@>Ov~bG3xBpg9HW*F7Wqv`VuVByi7xi%dC&ZY zz#xhfN8Qa^$`PM@RvI!r}O#?NUAH3_x{}QoG%i=bI7Yrk+RLV6lA@p!-!F8i7w3STxC! z2t+ZgVZ+7@fdH_es8}04CJ3-Cw{KjPDF#_B?2Rk1lb{= z=n_~AATccq+wvGaNbtsS1*97`9qpU7}# zq~2qabPyAp<^~1JWE=+!onXU9KcWmQfd(xf00&$jK?N;92q+x0k)_}})La7A98fIN zAq=nryz%|42c)-{@HnSO=QinT>Fn{nYK;NNqFn_CesCiu04ETqcUS<4!RUrHirsl(aZimY&ji-1 zdgK%43hs>ZaeVxVfR=_ST%=m&@#5{dEkE9acMt+$d- zfW^SkrX zoxX=RqGXC=2o8xUxODEM)(iEn{j0}_MZS6Sik&-s)b`bVXt!_Pu)M+|qs;?-E|HcZ zy}Nk!m{>pNer^uWdbpGjwEJOvuV1}nu(_AcAD0pU7JcB*iB?fLSjj-_`jH`1v&Z~k zU9s1xJ}M8!@wON@SRZ7~<$VX)_!-Ycj>2kHgRGEd;f1|)mh9T{zEmjI+~7r@ZSVc< zdPP^jqGy?kOM0v4C-PIC{r0tQ*t!q@$u)|Xx+eT&s&tKCWv05RNN>=JHI5?q6rQ_1 zci)w;xILfWk=MBE*I30&WL(`Fee&EMMjbIVxwmfKkmA9~oJm|b(;Mb#MZaNo{Logr za`CKhy^>*UBzS7JVYM^uiI@Jpk|}_uxBvN%w63F_%g>Jl2zwB4Khrq2LrtU-jRG4p z^>MjVQ`b!bgY${KB(&C1-Jo2l6Ov4QV~R{Yx{7EcZEgMp=<4QX;wR-j(fUhqoo;37 zbY!OUZIp8i8ZlXAAtay66KZQi`ikEh|fH=OLwzM(E19813ITH3PMf`|MAE^fk7IFA2DCnts zhiMJKCUGAj5ATl}?~(|p6qBKWN=P~*w$km&{$>Nm7-wi=2bVveXgoh;)HH!G0up3> zxX9hQemSbUB}hRMiPVYD$LSO!84e)828YenEA?^#J$quW10cgDTCdVRVsi+N5AIqk z)&b_FX5s?Xa$ybv_}ISg4eMPwOkj{k#Yi422h`Y-mwrzH_3EX6r@P9{$<>-7tB#2V zpLONJY1f`4A6L6OcKX;ZJFs(&4n)SNq^zIXP$1v>8Blbl)cX=*|CaXHM=DppKZ(RInJC+yLUUt^eRLHh%ikk{A=v0^X`e zOxE{PYg9F8jCwAL{kwThb57S>HC#29{5LFhRrMIv3m!YLMIdj|?B`VAH>Y%4{TB_bqMu z8MnLSKsBwpv5R1l=UF>xkzGbWDGJOUt}{ckbWaY)bqMt(hi6 zMb3&td)Mm>j15DpVPso(+ExtOQmc_R-`D+u?h)v~2z(;IVqEq|&4BEYOZr+-NrmO* z=1FFC_VfX}aOQ|M?+DzqkPq$h;*1UO!v+?)9s)>!(vX_zcJ|~xNyi+->6}n0)8^?8 z1ZQ8}T5J_(aXb6{9hlG2OJPDm9Br=N-;$_$TGb;Fe@j|1%J)WR@SH5W-k1qYLhSm zC@t?N*`175*8WU^`t$`~P|#j~`k-7&0Ymhy+PvaNk{>_u+25CW$NBmrk_YYH`o4{* zeZ zt98Y;b#JM;JL_@w<6jmNMF0x`=Fc#jTUP&6?K}XOj1%TDBgfAZlSx*-ZsXeu-syvd z+!JXgtsXGkDe76S=I=-LZxEvx=2@6`E^C_(7Tp6%1kkWeJcH8Sm1?kl8&Re8U`Rtdw`cd!^cKoc&CFr74EhbacU(mr9z z+?Q<1oX@DX_RO)p_R%}vvf~G~Iy?Ggg;sRY$;lw+BsyW{Gm=su-SMWnUAJ1*m zsvm1CO3JIOqF=RK|FEd<*{ec9^PcU??fAj%T1UutF}K+G(GP9(=bel5!)3$c`_tfSEbqdJ{WZ1~S_t&k| zdz1Gve@b|O9sONYQ|9)B))HxMuExUIj>yCO`>0Qz|LkvCzp5Gm-<5BF+jeYvPmYVp z3Yko-Vd~DAc#Y1~2&lB@bcoCTGP_Eq@6&hlr0vWp;NBBIzarDH<|gf3y(@=m|G#nV zk`jx7!AI_l!3{k{QBsh+DepbNP95K^H5d%{Tq#WEv0>gl{qld5?3}h;@Bie_?c~wA zNah;tQx8p@VtkBKPW=oC0)7QZBAJ6J+uCK{6)5&P3-4Xy%+b<7T}!0{u^p;)IcZzq zFP=mR^Pqk6v0Y#>tQ~r~4yutFgXf9STq60|zB${zt7_%5!XDGo{?gXpx9>9BcvVZH z-n;VQ-5>H0jKC)VEW#xCz)pemAZ4!ei;DGoEdI%$U%lwvwG^la*UQY}nJzER*n>;W z>ptjb%0|Zl#z9D%0~!inJbNVR(Cp~_yMQP;HfbMNj5BWT*p7nNlt10gag(elztC_f zyK(ihlM02PFXcvr*y%+7i{tT{?f-dh{$6Lv!ikDP^Xq&mA>kq1A18 zLjgL>()?$>CMIaFf9i98pmp%ko8MCXBfT~OoR~Ji^3aB0%A=pL$+JJLmI#1C zYQlPz^bvE9Y0i!f@5q4>=hgKe{XlFGPQ*(-`}>lCzW3^Xx4!*H*z6@=wtd?_7E6X~ z5WvCj00%4H`D>{FhK!mnrj)VfI%p8j>m`%*^_0{CA=4!ze{}yQJFshws}~|5iv=s1 zzkwM{WBQUq48RG^qN(k?CTWoSaV$cEt0y$-2}jxJ$&ZOiJ+Nz~9on}bBngIOKlb6`6#lK`F<(0~6uXy|0>I)g#N+cF;D^e{p)eFvE z@)gw;0rCM`+&6P~%AC*IrWHTdcaorhsRkrg4H;)+CN0)H<9*a3o;!P3e}{3*+GXFf zVKp-}Ki9nfU9~WxZ3zrCU=Z0F;|;^gYiWhT1M1PU!XA12U)ZG!r)<}z_iWm{m-VT(cIL!>0m{)+7Hf`TY;*ePE<3nqo%+53uvyRawi`2biEUl|Q}s^7 ziFWYtsdnM~ajRSRmZXNE3^cJ1rGv!)7?E|mx~p_nPa$k%&f#ZUhk`YiFk(#jO>N-}Koduf9BOb?X(tWN~;KBwZ0ui}uZrPCn=5NQ!55-zUA zP&{$?Aay0lr%6)q?*nS~IKUwLtr&aXgIBL@YL0*;b=$1wvc3aVhsPYI#vB7KmyF3Y zE?HVn^f_f8N6D~e+4pSoidTGZPx1YU`SU>gDYks_CT5XW7KJn0Pis^K^fN_OvSGz5 zO75Z1h`?fWkC_<2wod$xMk(>nYgsSVIskQ_(SES#TK&-eiam}!6DL?=(rEU_Ww0&W za#!xuA7=i-TUhrU+JD-5E-n52{iFgqdyU=i>&gf`q+l`JlFLdFC}Ivmpj+B!fHrM{ zD{4&$oUUCu7bRJP=}o{knOU*+Y#Ch{)(7`qfyL%#89@*vA(=UIa<78N&MxN`!D5=g zHy&y!nuvZ8io8`Lg5)#D1EqU9RPh7ZXVR0zE3Vl)haN#Cn|;D4#u<3H{AKdJw0Oxe znIH9TBgf8>oDugo7$uBc_)MfZu74rylV`cIvc!_-j9`#$zW?f2+AqcZd!>GU2&-g*I^Lc&#^p0y0q=)l=j1?vMUhEYYM{ z&q>-!1LPh($}KxD-$qTCuLkZPzVS^lMVO`Jbq2BJlUL4#BbU^ojkpeeLU#-Ekd&Xjtx@8<)yp2tdGEabULCrq2DW<{dIsoT_Ol zfP@sFON*1%<(5x;!lw309+SsZijOt2Vi5(WHE?QUY5MM4aj zc?XGjKN!)Re6jFzp7<3>{7^_NfBi4*)X_bX+oqXm6^hZk4C7+N9S^ZtP(YyK~8JNXz4*JL5yYCQtVkC@kV)|y`c?@nZzfD`I8CcwDl>i-R%7Vi|m1%??XmT6G+CH8Fde3A#t#noQ!E{ zRd(UwwFL${t8VDfCB>r4lq7nGKBoJ{5A6s%lwdJFS^@Y#^HaA%;WQgNfhkt{NDNgs z(8dIfAJkphh91r*nUn)`mzb5Mj2E`*r;qOz@C&~){Ppf&{ryaW>hz)_d2&yShc6W@Sh~JuG{dA+!?9EI(gW++QK@G8ar1R zYp@9}a{z*YL&hsefAa@_B!={fm;b#acdOt3jsoNG-LA&Q0UOwvnG3&U8(02VMoH)@9Z}og}Pv6Hc#Cz zw3x}x5m=l)|7F{=Wtr{Yxhit@Q!RK_mW`YKlvq8OQ`nY1{YOZ0&DEFvH{g&ZTp5dt*E$EvSs?tkxU`zqE43@JwV*%)j!c3teG%hzzhj*N$-A| zW5`&U|J5U>+MuBm6}ZuQ(!G6j8pgW$kNvPp0@b zVz5b8<`>wQDNC&1pc^QRBR_L#)VBXQKDS0Bl}NxZU`ac=R9i+hz>X<3zOVqv=3ll`WuRg0=;(R2UG zYNtG|XSx2Pf3o!-eqRZ?B#=xNO?=%(uype#Z80TW(v{yzbi> zxzWy?U`=^WNg(HLYP9Y>SafYsa;$Q|C>u02e&CP;96IOM1U4*t9)hVRndX9 z(hU~x?Q-b;bhnpR51-uf+43L;DJe^5*0Wb1>oZ`4Z1f2%u~e@=b68G%%HYHTx8(Y< z2XXNa<~uWOjcjIxJxf&|;cVzzt}X2NRVTiYpwU@?C)cs0fkgsz9MT%@DA0m^xz}JZ z4&=hzNFA%te=RFJPl3F`1wdP256fz9mf=Qg^C|#R<{@&!VWVfN?-VjqWTXdoud$m~ zFWH^OTb7fR8?jXZC4{(Z~N z&Qo(^m=oSRbI~u^fFa}TXW#vQ#R@(7@_&%Q$eQ=R&T3>WjK>=f`&T_jp5_cSy(^%Wjc9fj%{8^J>Q8$z$u0@ zwkmc1^ssaw8K61$iC+^lg2@mPI@(Q8(@Hy*`qPKB=D8lR<9dG#d}fG40BsAN`)$1! z8ES*?%Lq_=Wbv16=cacg3wEtfniODj?*MX=QY95ta1H6lo0S|PR^7MTq zK|lar)@Pt?UiGT#L;F{cmcbH95o$-7`^-D;YyXawGQh#OiKGk3L6}9HLHV4mYhHI| zXO+Wj^4u5g{Ha57Hl<%Frc&#d{lMza98^8($no=42TIK_a$agQasA!5{X_4Z9h2Kd z^UJkoq0eaT#Kqbdcs6PYl9eMf6r`=NrT}f`8#Tqzz7jPH_m4NtQ`D;;a87Q#tv!Ts zr6w8HmSn)5?H}1kZ~iYyYm5b)TjoF^!ZI=8=7qd8bvRI@o;c*MGQLvyeaw zU@^EAYN(mH&bI5bDZb?Iue%iBO z9`s1x!|!hiED|ir?JgRh4rHrZx!(Bq@zMDOh1wF4fVH0Ebv+9e`uZT_9u7;!kIp1X za*lwBv7vskxM!)1FkFN5(910OBLQHzd=k*%RETVheu4yxn3>=*N5}1$nEi5ns!BFP%#WS|-^}m$#hk$+Yr~i%C%Uj?7 zL)FDmS9s#^c3Zvl?*%mZegHv_UgdW6%6Z91XJ3%*8O~={FNQlE zZmZOG;hu?sPE*qzfk4;+4*CJZCd#3dmLB`+R!S<0$%%|+poKhxn3Rl4n^DwLyV@=O zh2(Pdq{mc0C^MU#t5x?H*j%yNFh`AzR@kG|rq6p>|3+%by(b(J)AJ~RN&pwE#gw_9 zRqsk#y&xAxHp?79q7Ps@clL-_JeXXVVpIju^iHJx6G4q+sJ(3Vl3&r>r9b1Ho7V+4 zk+?qc_?OjM<>-M;-tL~~;@-~Or+%EdrPdgCZp-w7_u-Dn^TXj4=_c1$*rP-;X}%Ac zHH;=kGh0^uMC>H(Uc_cjyGQ$hO>G^a_iBHn#%L%p@)BIj%Zt(oUelj& z|EN1#@6cTgHT|8|&;cd66cYU|qYwa4QLg-sO%oj9jkmTYg@S)p1n`KDnFi$j)}B%D zESuvDD=;w;}8r%mF@4SM?T^M!$jXNV(GF>Y~k z(<(X_eB`h-*gZW!_ZddW2q^Inq1iGP{pr_)#mVv#*{7|@*I9g>^GdjNWrDBB(6}65 z>p4mkBq1BUyBxc>(Xk6PWUfuC#{oWtwk(vg)4bHl<*Q!T2H)OQtJnmCrP+dUZyA|B zTWdd>V#clblf0-HzCLnJ4&RR{($Rp#d(0vKBjsOWw_CBZw#RF@wkK)aHkT&SV^>X-kAASk?Z zD{o{y1GDp2_8oeFMBqN7ObqBZpT`Z-o=O-c{x?sMIG3B%F#PLEiR!C_XHGfs`$PlZ z=);Y3fRRSGu>%4Oh$l7O1WbWL*ISSPvOR}vaY7;Xt%#kgCAKjK)e{s>?XLS9vFadh zPBu|m2mPVY%-cttMcyw3Nmdo2=?3OSR-=oS8CUH7Nyu;)YfApR6q^z!c4Pv0@oReS5bN1g5v+m!s*?(Ga{!v0zj501xUp_!zzXKNMG zWrLDin6ntJ`JM@kQ3Eqvcbl5I+T4;V0>IcIP+-0?w151wlsoXx2W>_R(nGstOE*jg8;;ecFq+TAknQIW1Q34UGjwb0kk>3F z2Et)+ZmZ8I)^0klka8>&RCcV%f$R)IlUk?Tn2k7kOMM(7j_QHVUz~+h`$RS5?}CIm z0s4OY+#R`-renFLVyDd<6Q{QSf%~7~B5NWU{PG-KAL7@dsK0}{3#J42Vh7)YO^diI z4eILwzUBXeKT5BHGh04g4)fBb1ndJNUT7*oj{Duf%jiFk1B;yh5@=se%V5;HVI6$F zCoNXT1&baFAR&1#bs5E<9tK1jLm-9A_FY4uHdK16hP6(K#XUP}n(pS~F;AE5-2!Y! zZ6GfS==Vh-EoFVOv1v^W^dTN?7ZoE~%{N&zP<&n3_6o>)j8yYGh+r}~%`gssu4&<$ zHlvi9riiwChOqMxPytqAD)V*(b!-{-{q*Y_!uZ=-o4^Tw)c}G0=G^176aA-2deuJ` z%9`J;#H1#t2tZ3D%dN`U!PqX}w{oPBJRWrolA?C0BHqN-AeNOb@9%0-b}?9-4?^Y&79mPHU5FfI$K8HGh^aJaF0wi9+Qyvcj!9!k zA(Yosg1RKhD~FzE6`>py`uv1@m%u6oy*GozNSf26&b;xveEN5OMTkD zO0Uo3-;9>V0o;AB2OYN}#^$G7(pX)m&8WoVGpUOfP>OD<@u(r2{%W7cWxKSnH7z67 zR;XTXtbmhVGNa*PudYL!1Fi-a!WuAoi4Z|UCIV#&Dl)+vpHNc~KckT_HL6ghN4gW3 zqSo%W`=gue;i+4J)6XW(R@qJdm}7?2`*WIe_-4pouTTTsUD1Ii_us3tvYy0oD)i%h zOKcB^iq)5D`=K(@-TLLX&-6(2?$I2bF2nwZ+VN2%tiI`8i{Ytf+U7cgLd!cEjX zDpjY7pcc*W8r2slC&>zul&>xc;7r3j4br9D36DtQg&zvOieKZ|PZ--6I8ct4tLik_ z;dgr(;GDm4GMIy`{niA>=J$@zIuU^x2BqDwRW#gYO47vznIiLf8aC7!IWfYorsfMy z)$gj5s#wzYHzwNlyNNoxbC1NYxGDV$Ze7y6GseCN@!2&W66{xGz4C8cbyM5ty?NgP zB>cs(u^(nO6uyQMEUY$GN}RG!oJbF)8bC1ioYxi_=lu+YJoAVl4(X(AZrttnr%lSf zC$R6lHaG*KHfOdFN(D&*b-o1a9~yO8K7c1CiZLA{ti05(#5CZ9p)^5Z;lnMI&gxpMuU?1C3iEvS zuRK=NIv3PB1V%`3%)M69-aqI?S%`Xml9q`dZg!w_rpBBl#65ivotmNh*Stsz#>4L2 zpYM@kRu&`6m^5dH?~!p1h*W*$bG{C^DZdX}=k>`IMd6%D4B;rhZt~#42Redqy8cuj zMb$hsx&NaZsizmYJ1zIdnHz&v3Z%3qp-pq%_@0x>1pbm|o(6Qo=|pS~=ki0#BBTvR zKoSuNAAAT`=~mP1k}J9H6Z7gLZj^Pnf3Y9L`ZrcB*idNKj9m0cj$SB){B%5(mWnv> zWAAGz>H_?i>A#g?GV=7wEURVoC5ub$3`24L!Rk3me5_5GUl}qP#9u2qca3;{Jn~8-`WRqpq(IyQ1do z(%{t~K%pQQs&Wi^&+l-&_MInsvU?9}>;;Yr{j!_@rV;kM*^oa0HymS{^+()UmV&;1 zhZO=GDxrO^PYhwX z4Wj+eaH-tPMPUENPCnd|r^(lbjKtLJ+dk9CkR-8e#;O#a+T1t{{{dX=#HCvag9Lf^ zakvk>Obvwn+XGz25T%ejTwAe{kcfFNA@6_SOablWeuxbo7gjNAT|4(TqPw8r!lmOJMj4n&u~fT7zkwKnzzheJPuyg21lTn@$__h& zh0cTj+DX@5?oi4DButG{!n&w_MwT!bP7_mxZIMa4Yqu=I!Qk{h^ju?O-C`lR2l;8A zJ<61qI*1Ik$7-{gT3W$PFOgYDMA&@Abk@+=t@#M6VMR-NDRliEUA6_X3& zZ>%WhnySY^n32;Mgu8Syj0MeqWWs5gwwV#+5lA0+A?C_XeIw)W==)Bn!Y}5U@Zw(X z6rrG%zeaClRH0YgH~_1$df+wCOh9DTqsE-l6xx->$;Byy!Eb(Tj9(8*G1RCW1^=d5 zkAy^L)s4XK+Uxsc>$clvZt=ctjR2zfdznHzmLe`T4 zi4j|mR+?%D{7%<~ta6`TcHFuBnDm121aoMQ4rNjBgm6Lm5qV=&CL?>x!+$||ms0eT zj}sGlh#HsccY{F17Jqq<_!J}kqcRtt$L5xj%Wp+B4yeMJb4PsSpBj10DM+c_y7AHz zbqvc(26EO7YuGX*(BNU9-3p#97!}OW#dKv74vTyK8Uap*zBh|0B<8|tXDmB*jDpR~ z#>nc(VsNeBGNzCGF8Sajx+RHg&BP^>H|-^w@#*&hCTDU6HKw^hAsdW`vRIkV@7;_r zPb|Gp$z@?#)MleUwI;(7%Y~a2%P7k2V`?TeFJU0m=N+*SdKr6LZx*LK%0E1- zcmEX9zvPISLtD zBy2akexT!PP1+Kbk*=B5=JjLv$AZ^=$>qMmhZx2~PTDWp-jxT_6-TA@+2luMIU?gU z-wZA1>}Ql#x2LjlKL9BpL`Fobl!)BxQ%UV>&HUU{2oiA zhES4l7BhcxS;u&d__>+tpE*Kxx!S5icfW(ty>@}p;86ksyOAQQVbAH!P(t*FBh!Bn zW4(hDNdlKkf64)pGwk$L`z z1U0*P(vcJeT%dkEolV^M5h8Fs47h+93HNl+Kh3tQ3W3XP0m<$7(QdWnnR9WF2`sVh z9|erOVD8v+g&v>lZ|=7VH|wDI)sO2TgVR{f^@ns%UVKMCo%;h2+Wgml$NjYpCbRq{ z2GC7P;Y)?WzH~@tePT|iRcLh1r+F`HAe_71AaSmS5Q>;=0=NQje~bu%cQn+_pVKz2 z8FQgPaK;J?I~Enkk8X(3#oW5DBcLVk^FQx%er!&t^2#jgWQ*!uG$Dj|cU$Id-lH!i z;d^87%#Epmyjds_=+~+h3FiUv3*eLkqJ-B_#1R|V)6{4O`|f2ryT2JZfCEy7m^uFxyc z;YZvgXn*;67&{z!3F+cg@IwFU@2!}_cT6slDud9UX+uPUo4<+j!ST91J|l!vA$}H4 z)hb1eG8{;5gvE(P;=>hpkOqI!BP`uD$-A5MQZi&iPC&ZFB%^KiV|V4rUGp+^g7AnB zlL1N%y=Hct{PQ+`OfKxXU7adZ^AN@F;{AD44H4$9@adl=v`$bezMbh|R6$ z9&ZS0n~N-R)^p|=fHC-7^>7y|3cH^KIU@juV(EPxuBQpe2e*Iy9bxmEEQEk*$(x&b zIVnAz_MV2D)?hPMLn&uPdW zN%l%6iT=~kclyaF>=ipA`O?6wQ-F>KcqXz!92JZO(iQ4|aK_^l!=mk5Og5O6C_2%Q zjxWq@jSHzHNoaZoaPB%o%*-D6P5|^Cc|4(29ZaGigMiamE*EeRG$p`9wl!>CBJ~Ub zrSNECrJpQoAIk&nWdHfj=4D~XqUD%}!)UBApaL1=vK)qli%WBp*ZOY?GsK^EMS--D zF^2bFsTc}N*-dZuI-aWw=h3O4)uwI5HKNf)=w>gTm20eGn%Motl)>B2M;6UbPbw)} zT%PxR`mH(7qx@X9=c94e6t(%(aK0oDHg8jQ8%?Jyf_r~{IP#(wxbC2o4k-9*gCUNN zyE8i;%-tHgXus7-n>u0@aLrVozB|7O2H%lT{fmW&AcfnFE{i4+9Q^`k7>VSaVENjN z2D-|3rkx9cGQT-a3=i`vs=}>eDaNYUd*gny@3B{DdZt3~_)WFe`GwV?Sf=E$MMgN| zT#)An@K4pi;;kk0!h`^Mzwsj)VEl!2cylC=Lq}5@AD@P69Uo3~_C1nZyS5w~cJnti ze2@EY2Iu|nFV9_tEOAf_U2ds@`giLd)_=jZyyIV~^25WVQDYB+!^Gh#R;iLRkTX3K zpUeD(x{S4r1sHS+bRV&E+=AA4+U#=~1c&OP)+Tn6i^Ex3Qu`|=r_L3dJ}9S*s!~9R z#BfBPBPPciXExrjSx2k7(tyBcZJby&FD*=wU;IE71izm=qQl>KaTZvdb*IzEyS0z) z4(`n*0!?JmN~F1SR3Kc->;u||P%H|N`^kxR&nsb)*i!w%i$yBerT5J)D)E7su~9LF zipu*I+ND6Qqf?#rZ8&BR^(JnN0)u3Y3_=m~8Ly*u@PSVXAPLC9_}x?)uxj4Pl#(^E zeqlA|Zk!IFK@am}0*U5WE^h6M5hI{!i^!K2Uh?AfnemU(WJ^mLk%mDM z%OE!{p6AxiUrV#i;Tklc@;oFWgJyWAd)@kMDPSCuZwRuNlia&cKXZ|2y|Ekhyhm^T z?ga_8U0I13DqQAT@uEiVGQ`B%5un=vSZg*Dw$-U0e~0X>HzRO`MS~&5R#46hDGwD- zsM}7jy{rMb%AFnYs^0hcoJaHahSQOLI8MV4t@exCF$T<|z(>oSJ-jXq7$+h-a9iS- z@9L-Z?zf1auFpLzzarP$t_LA+A>Wpl<3yPK-VILP4GUsaW-3wClPr>lj9X8Tb7C#h z(lty0c)Wf)*P^r^M&bCVReIfy^=OMARZOCNq%5y4JH_r;w)jmf4OxlT*Ctt48Nxhn zaiIGzY0*NLaa$5g)hPtyGuq9}e3b=N?Nfk6C`=Cz0tmU)VA{V(?UvXEMuM81e0#0Q zsaPL^$O^k6tbrbw-S<`KienJJ=-LWLk-OEqh2hZW`@*jLJW|y0?EK^Qx@ErF>&T?F|=u}SOq*)<2aV0iYsHacnhi{gJvGI;Bn7<3KyaTpNFDqWd`#+4>Br#vPL zBwY&|)~AOjD>v(@aUK>m>C3)Fi!=l=kq@Rvrc{Y40KT zd>f6n>ytM9tNz6Jip{pvLLYIIiM!U`JbzRAIG;FsQsd3I{)5J^4=obpS8lHuoJ!Cl z+za3tF%Mo06+faTDoppawWHg7{##ccBMdP@*6tu1J(@|S z^xwBN?1;_1MH$3=YVtQ!u4&9#XtZiN<{Fw{e;7vHi8x40Ezq=mF^q~}4v$wrOii>t zBpG#b59&u%SZwvA%7+!Lut5zKIo>StrF=Vs(teoYb1BdCbsUO>^&mPcC;u@D!V&D> zt9PU^{Nl0u9k4Oa{`N}xo!TvW3v8d2^)w%|rl6QurLLZ29HdN~bfpo##6FR~!bG-tfUwkqAHC`M&NY0B+{X1%{ zs+9XumMv)s^JjhUL*o?j$s+Vu@yU_J1Ws;FX*UGbP|VLv2v#%`xQ9inmkm~jE(&#F zKiW)y(9d#?5#}x!0e%I@jXnVR$peC;uD_LGx3#@8v`=~t`FR@^n#-qw|McT7t{#rL z7uOiM>gs&Jngy7l4W-HWU0C=O17b}k`ppg__w(ggF{VIsT80k`^`%1CKTHcNiXoE^ z@+u2?pg`D;-_UZB=qjMm#FCmf;V8T{I)c+o!7h3y-uwR87Qhfh@vWY<0f$<_Wbdcv zY3fd6z)QAZ9h*6`MN%8t1s~eAZdR9`VZ+U!bBwe!r@Vu!sp=d=Bw+gN1r9qGZ7TX7#1&1{C~ z4kAfau82fvuz=+;Lwk?)!SP6e3fu$j!&A|D(LV?1K7^Oq3 zP85GK@?=O>3>Qhka9wen_U8lpbgPdWn{X}paFZ2cy*gi%s|#3G2(O{v1{$o+48~4> zyLOoU+^sbhd8-bQ0jZTUY0U(wu#}TBq`3(0^?D31dR0h-a5rK-c&AX9i3@3XyWe@R%nq2rdI0zS{%GIlP1ym3ajG~? z@YybJHZ}-G{2zO>_o%nk&^N;)zd*KFG*FFmyl4re(;!WY7pGpPu0}a~$mkmi4a%w_$vQo2A4de#w)oFX zR%_X$P#BV_`s_a+WG}d&*aMK^E=N<+6kk9P|MX`{!9RPXqFA92Q#69lmZ{Lw@hJDd z>N#G*DpwA}!a46*6)xJJ3)uxBPMhA{I&jp>c?ssUVK^w?E6jU*?zW&Y=WKmeqs}+~ z5lX!HdFWFg^9KEjMJ^z%TB;a4Fx_1EyGC%arfe^7_28h~Pd7L(M}s{)aPQ!Mp=`M0 z8QLVzF<{sGv*cXnyt=WD22a(>D)XhdR1O&d#^QKKgw7g~*47FumU6SnPlAa)4KZl_9_R=raBB5ECaMzV5^C-rY(IvCyk1t_-VkjabO|w2*0S=qcA%v39!i=E;%;MsyD7g*elfy&MI zIV-2SEs|1v4hxW2I&W5dFNw^4%DAs+cO_k}$$k&6T#X`sgwJaXJ|>N#qe;{fKkM>) zJ;dy!*y{z@(|jlLg)(8rS9C$5#Z9-lnQD!n;*cjeJ4_&sS#T}LT-n=!P?#xF{`VI5 zJ^j&z(t56zf`JLd_AXVZI`itW+zL{NCoOu?}uL_ehA%Plf`sI9BR%9(Gh9z0TEKKqD5z} ziNTJzwa0gg|6&Q^`0P+Hg(zMk-Iwtf;uu-yUwU3x zV(6wiCNMTwqEi+LFE4#VTzsE=BPCC9URvjI%|6@~tVSWqZa%W3zLqkw=#2L)Pw{@}Q^#+(#eN?lVEHF;-{GJ-9955#U)v^Q~B z+H$o2{K#im_=s(+u>4mkdq25UH4NdVv7|eEQ!y!p|CTnU;u0!{wJrLD+ zhI1|^v@+02kO*_vYACgTv&?|%4ogm{H$xj@I_N7wN>YF#wbkwD)l#@K=qHn!G2Y9? zm!lZ8q4}vc85?S6lv;RXaKWVSZ~@a}8#c~87M;%h%10G2lL+4v`;IaDTZH@^(oMpkSk)ES z&J<T~w4u#i%`Fg|tK4ZD?KEMdIQgap#niZ8gH>M+N29{cBcQ7BhvN@-Hf3h6I z=4H!lYTf0XuXxPiNcT$Kh=2O5>d#P{*9J*F$Xba=!$~jm4d+62~{G`Fk6ei$nRP!L5ewBOZd0LMPw+3J7$q8(xu& zZNM{naU@6iNMLB*;#_p+D-TM!bio!)sk_xvZf;y#V~$a1J^KU@tVmwQH>6^ccB_Bk zW+2O52%j+tsrmb*V^Uv})+eV;5$qU;Avj{f>=rCs(F@3HupQiMXb51V8v2Y~KhQtY^I;!=dY->7WN^_d87g zQwsv>1IC4&+v#;lN_U&*=+jlQ`^bnNZ(+V87*GT74iiM{ObC>cbp7q06S{btyz8yH zYM53(ms;EI_pl&bl1ua<2PdKU!1+&%4A-Pl@&ii958v=F= z_Hhr9lb|>ttpfeUQM_PW%wZd;oE+2$k~j{+Q$)1|pDqzeGG{YwD3udaJr=;6^!?BK+b}SOF4_7`!f*-xUl5+Js!iX^!A8O z)LjgFJndxaUCY4|Af^Ydr)k`BgL!Fw&j|h03(H8@gRc))=Lo9Y{ALpt-{IPvXIs-& zWh^vS+^~e{i5rJbAo8QzFYSq-fY#0|jySsoPvF7IKCpSH?fXI*%FI++<2TRAuJtu) z-Q%S}uf;_+!s@M9%xc?d=Xq~8%Wfo^T31ac18Q0q<=Ut)=9iphJmpR{Wfh+H1S%uR z<(X;P)@^(jMY~(7>&+M{Hmd!vaea{*QsjN>yl|@@^fG~R{_V`w z693?FGN?9M%r+Y_L){;RiaVt2>Y^L*@f$vzNJ=zXs>$hD>)b--kmmwPm+I9yXNy&) zqJ)mRbQ=zmFbRS+*^63nss+Us-_n?)L>9Y@tt8oTUaPy&ACyQd=V;VjrZ!P4$F~ZdU;oUf!+opla^HZoEmA>+uX9-q-H5PtYM`%!t>wp)W`{ zPm<3s$}Dn9=|@X$^~zc$*M9`owo}q${qV6>cex_KTN;e(B>{4(HGzdi5 zkqYj8B!-654hKVUmCndglygUI9fQ#T43_$UI7_Ba}8;MED*QNqjW*TbiWdF&5Z@xVRWA72ii*~xL zKb|B6p+yiLn+Ml=zA}7fZUn@sOG%u<^}rmV7$+iv{Z4gA5XdzD7kX3|M9YSn>c_8i zy8KaYFYn@J?`L2b<>zwI0qop|-p9|N!wbBrtdXW#T~A6h_2(fl7#Y+@m2;wyabd9~ z0i8-rB%bi#vwD^7eo|kJUn2?=@pzi7>(9zxG;L{iw=w3C3#7$zB~pz92O|6*NfsJ*i`$&J6&dZs zzB{?;cDO7wlzS?)k3F7J6+6U;6f_mnjE1SYwUMFx79&|U(R7< zl(-oj(^@vyMrn!Ft5#QZmS!(D=Z@YB401jV!Q<#aqFHuMCL}hP-`R=vNL_Hu8*_4& zNQN7x=74A@bLXr6wqV5*nz?+Ydix`ps}th&U}2%rMKS){G4*?EdR@AeGDycBz~y1ImK`ae_$5J&xV5`L8Fn0`KYehLz0;>J;}@M#plP(mVH+?{k=EXQV7m5IL>fIzkA`LtT-?6 z6^4kc>y${M&|9|Aji+sY)mF$cS97NKxb~agkI(3$N?C?D#Jw0qI6gq{jWY(P+; zWAG;*7k6Nt_8*#tzg8(~Cq&gEX-Y+{EoTgf}Ial#L4Wl@jC8O@a z@7lu6bdyHU82Ve#>-?zDtPyI>KN{ZNZy9%GYHHDH3eJF6H!(@$Gw8CE(1t@szs+MdXoOWrgocV9m9Ub5^4%|y-odB*q z*ZmkWK0k+6!2ZNKKtY?;E$BVNbT*%z!nsuMx$<@n#}BC$6ryNVxW${V$xxy60LS`4 zu_HgFx|Ew7NOAnx5CVQTE!`;H7`SZEG=Ifl6MQdhUIrNGSj!M#2u3aA{?Drl>M8vB zj1N8DN~=fU>cdUK$8PgTgnhPC2>{+h_@9`5O^zKbd?F5Yk-1aEufJU_~twu_WcC6(;$wOkkvHfc*~)~Y{Sq= zEN<&IOfc5l0$xO|b#ZqklQq<10<3M?L>qNlrw3U5x<6@tM0`tSg274sPBHD|f?9tr z)7+wn!8jyQj47f0+b2D(14szNuMrDZDGZB#r@E!{y$v&{2SOcj_U9Yd0o{B(+Rf?= z@3ltX+HEo&X`Uc**=)w-hm{vuJ`TitXd`S8OP7vOF;0e8OWU$nKvOsemszgB{ZOSI z8NtT6Xj#GZB9osTWf&rS4XRy&t#6nv3H~Lka+DfDNk!lCCi|VK`R;Gq(&ZJyf5bfu zyY8eiw+_WUVEAVBg4J41$~G_sT1{enUKh$wAh#koWhmp+sQx;z7MLe?Y8c28r4(Bx zUH8tL(!7bg_S+56$RU`r`kDS0s&2*SZeEcuVlC3WnUeX-8aRK zThhIJ5eCBhW+;A*N2OKCB$eAFO!O>NTYiS>@-J;v z2Zgf*rPJa0kdfu(ioH2MKR@2cd!eG?F&3DQnRM$I29J0>H2&9z0z_l6MYg4-eX*8J zHBMmT6Qp(fPR{>=bw}8Cqn3&mOZ@37!s@EPo?;jw;_`RW%q#aEoGHa$bnpileM|bG zb(>uVvff|)XR?#uP6^|h(Yq)Rd;!@A8Nw7G{TT^HgDtarOE0m`ZGHxln^AbgntZ!o z(>2~SPtbGt%qGI)LOMR;g*9H#s1ktAVzrsB{K|LtR+sk#Z0x(5=E>IrD*~BwB{@lk z2mlEmyk9K;juaj|`Nj}{b!Rg+tVRL9@8EI9sPlZBy)xYE%H?`4#|7AT?#~(gDR7rT zF*}B00Na3Twewi<9Ph2RNc0TLcU>{;m3Wtkd_6Y&23a*^6-%EbP@~HHv#MCyo9!7a z(QWx6PF_URau}y+}frQU?jU*d||n z%_U1jI+6q|>w?Wwops7p-HH$TD=yAMT*Tv4*4?+H)b!lvp{}2DsA-9mA-@+Pb-f<& z8DXK(2YfkNiE_rPCL06Btvnoy&DQ_WO?eD>;|+*-N=mXY$k}?(O!|pB8!Z;(8{aA;u|`!L z-x4r&V--53EHH$TVQ5PSEAx_BbZYv4<kJgE&d3!>! zhBU@&s8fFo?yrg(=QU&Txwnoh;*e6xVe~#DOuLxDd#px2ko372<$)(Qe{N+>sJ@V$ zQ)`(-x?xl^6W2)wZV58JRf|j?0i@B$h`|n8*|(aEw$U!u$r#x8Z1?cTi(jaPn9XKKU zS>>I5oexoIQkEqkdWz_=rFp!cb0LN&{K`)B6U=7nd|Q|cM;gF^OhGn$*Y6zpkGl2# zPKBB32053zlI~cU<_T|r<|g~ec9elG#t4$^7Z}U%_BHuKI6wwW#e~7rwdoDyORs}x z)j2F<1@C(n&GsVKlC;w}Nndj_yNuWv z&W8$TDP=y%)OcTN^pQU2O-XQlm_#|kWhXT)1H z#SMpjXyg!o7@g;X`{|1JA#g+o0Ta;j?(*cx(`5!QfL=Q0>M&c@YHpz&kTK^gX?L+9 zxq+|Zuv>{=@E_s{&_cF_H~bpu0MdqZ(c(3Z{puZ!6Tek#$hMHxD-~~tWfGzm@PZ3IfBQJa3h0rL)H`7}|!!fIiPp9=f0bHS+`utpNOh=3e#1?~NHHB5#BCKB^*Oo9O{*(rK0SgtXR#Vzl+O zyt;+Y!zYU@M+Byy=jQ0TzB%OCXnxPQPGzVjpR8i*{hMVr zTK?_}1xYNBAi(a{qBPoT1Lm1&Na%gm&ZcDSU0mzR-n_CuS4okX*FPhsxhlQX*xd`E z9lVV`Z{3DJcM#n?oXW9-C5F&4I+QD797Mk=S`NQ;Zn|*2W<`oUz_~|@jKI4PFqWJb z44b{q;{YCAvx9wlrCteSjjyOP;yKeD)$ZwbKFX$HYTYhB!JPWFODH(2+yxJ}YQ)gt z4@6%>q$fYpL4+DZWTeo*#N3LOF-AAs^LO6qZCHDj!l7nG#x8sT16Jq39?qdRD6=92 zo@;uv!m&1@{u2V6LQDZ-p9cqm6-?pyM+Q~ykSqd^Bp|4P>$ldJWN7LI2V8i5(E1l} zLTL77+TYD|VxBZ!s&-N`ys2IIOTn$yHD_b*z%@a`JL=7G&M2Zi(Wyw9+On!cBLbEM za{%tl9nJHFTGZfo{F62W^`8na+F0Fgy^R@e66l&)8npLQ^(Br)g{>N@rve*5f@$T% zGfkM{wMww5~Fx!*(HBinoQv}8*-z<6Qwu_IuT=Tzbmu!g{)4v^6*QEz%=UVDtfxHadH=!bI)>8i&%xF!8+n3AGOV6WmU6j)NuP!PBw|{pS>>b9$E%Rx zx1_>WS2ul>oUDl@BwLZZFr2<$ei&Q3Nlp!TWm zD+)NrKB^iIoA-8q@eZyxbz-yzF?LpIPGTI)0UC}{cS`2I+Y*=T_!Z%ETqwpF5_oW= z4kw6@itC5Y&Ebv#&>SjM3QacikYD*)z20$Vg^hop#BjP~nw@4DY1=w!$QFldF>6;a z^?XZcr6xA0^$}3dZh*+{Fvp2kx(ym38U$#s&tM7aY?V3k2U3Ch`eXj92S%>?BMoRl9@b7kw@=cD|J4OtBt|%HnIQMnOUO&wRn}F zPBM@&z~}NgC4%`#2B>Gr%&s^?-<7sWnVH7x%+7kT)w4xE zT{vj{;Nq}qCpBCXN3B9Z&-RNK6WI`i014eq1hRR{x_FroeAv?8f`kmR>B_GW*U#{t zaPPPjy0~eZeEHq}7XLw4o9atcmTtb&K3?dI(YxC zZZ53Cp_!%E?4u2i^LIBFr>9JN^owOa8J!hKY25WJElDqRAE@m?EM*G0aK}wu?#s`F zlHub3_iyQr+*}I~8a%msk;qFK!XPZT+rL@h9}V?|@M&)Pt3wdjC>vFCviMFA>{rBI zO>eK;F9&mk=2C^G@BH~WaF%bUh{9frOrxN+-yA>9OGY%}RCh6JEa}Xt)_DZ7tvvo_ zbdKk9Z@JHCmkE;EKiubjmz~5%_EX9$Te%G_+0I=@sIQ*OgGFFk3?9#&w6NX5sQw3* zcxN2))YCiJLLeD{#QX!p(D`HDbzD~3r{$~=h*QF$zc6`E=K*?h9-=j>=s6QfMkLWqFpMG)FT+Q}C4sCp$3r zOE(l^)Xa-Ap@w=XV#&IR!rGDMA%z7-BP$q6Z1c_&o;5Z?y|_c1wK$JOe`e!7lu;v~ z*)Dz{<4$xjKEKdjMM5aAKIJZ8t`0Jkny(~xymiX#iA40i!#X(F8mxJuXNTik7sPj6 zDTDiez9!ts45ROxV`G+bvRF>`X30(JQeBy0tKPbwM$ffT(jKgdHcyLfuF`#zlPQ8r zT=NTQywmiXCtQk6+4I?bYKh6oS~>YQB}LJUvXib@7oiX z=Zbu3Nh+lY5~_d|i-UfyI)jt)&2k}YSM!Ma-`9Nht0#8EUI9s+jV6?BNhWf`aCp9Ol!8zL|*%DU33fqWS?#ipQ8n39N*&;SC@0i~Tc7QcWIbq;!YNjc2&W*zo)^geZ7k1Lot-{#0A!2rF;= zZu^hS!<8-kEGzR-NQe<=XV3MC5v2(NY5~=0Jr5)2*&^vTPTeIeVTrj7pK`IsTn>dL z9sHlxV&NI@bsC4qT=YA-K1Ystl2%3Ffyk$^f0SjEtgz=*LRSsp8fimlvSvi_Iv4O9 zm5lTO2hiOZgYi$fO}eNZb+UgNvyr0orXo+MRCbDBS>X&Zp06e3vvwz=Vkud5-cCu2 zB}SLx*drH%XJ6_Ejg*3rxtkpMShr2bnqqohohsKz?K0|EjQ$VvKn%Z(+&&1i=!5sP z-hvUiow<%N<77{`O^g+4sdP78XgWOs`GclBv-H$nM?xGX>WG zT8x}#E!t>H)_mDIE}yoY@BgFSxZV+yQufLTcIK>=>hadqdBHw>^S|hv5wjR;W0MUm z##vtyAvovK+mQLb@8e&})G5w9$LqC{fqqC1H7|Wu?}56~!@GZD_wHo@i=K_7ea;JC z{U2>g&1~&8)FB_=|AF=hJ#3KO`u7kAi~3F(tGM?%wq%0(JXTdVS=+gzTI-y*uEh*4 zxiSB)M8YEcrE3Y|5(%ua((#ot9>TN*rA6`BaOYNfO3Nj0N$G`g?l!Pv+s8P2bTT*m8JVB;R+>pGw5& zJ@hNv2`@OY_dkm9Njx8|YnVrMGZ$OysXcc2{0Zy4(kgEWfFbqXl~ZTf;x%7Ztt*KQ z%zRJ>uzpV+-Y#Y>RkxfnYa)J^9DiRegNkg%tYtQ#a=KYxkDWVx&^j-lie&vc zUTGK~3&lLK@`+(wW%O4@M_{BzAP2A*&m3`Jk&$eYe2N2~tR@BXxH;a7J3hwlFjtTm zekCq;A;>^F7^GQIAQm^FdL$X1ks9*fvFkjcV9`n0oRo|Jy>aeZtDC(-G7{vQEr++- zt()Ce08lI_)aM53nHHDb@OfMm$v7gDBS_ML3%hmit_zerV-OgDOj*}R8tI@(1W*Wu z)pM?rX7gXL$u&*Z(RNBq0tYwJpl4qF3pED*@Hc;>H3(}-3xhj1yX4>p`$BKYl5rEn zz`^>EF}`{Is$4!{S(dK*nw*OX1dr@}S8EuM+4rDFAcWtA(E$kZdw?10t#CiZbrgvf z&BDh|sM2@QqJsc);i@mmQ0J{5{hzMgLF91h+ZsfIfJEQ~0Kl$&%vc$wAWNk+18q-e ziGX1iEF8i9&F(8|FM=~&P#dIJN(UI@3{{HJbTvdIxf+|-TK$}rcK_~OJAU8;Yim8M z;4pv>$v=bKG8d2-mUd{V5|@4UIXBJ4YhSh1oBl}O&-1`C5qviiC4g8$Tf zz_4VDSlzh`pSHXAZrSnuo9$f7KIdo|J!W8g(v5>6iEI?S54QgVw#YYShe@P^iSL^# zFyNgbgB4)(etUbg9(ZR9R=zAZQxbgCmxk6gv}vIhta08t_5HkctIIxq=Wp%ug<}fL z06nl@yoc$HOKjEC-_}{f@A2H4b6VRmnO_nHCz-FlK5Lk}*5)mLUU!cf5cO9N00L1^ zpWcTvX@ca2xle2e45{bW3U^3;lE<)&}jvbA5)Jc9Ax^6USs`of5fBq2&o zvuAhJu#;@JU5 zfW=_G#2)v`cm8+p$b8*Cdh@^7!QF3VZXq$yUh$Zi#c&Ssu2~C9)_q0wztkeqq9?G& zygS}uL-T6Mwc9VAk`p$HkD1MD42dquI^@rsrA~hPy8#wc$~G+`B}6!DsaHfjhg|*C z(H(Y+q?Y$T7;I_{@9#%z6Nfi$qrdeqM_^E}@qudc001BWNklUV4_F zuOO6qi5u72y==-gnoj-<2P}r);lP9yB3O@tqlY;nqu2iYjX*!CvpIu@o(DSg=PiBS zWk&DZQk@Aw!2SD37M-Dm7)UR#$~ag3!NC?z;sUk~IT!#886jDIq>)DJbXqKUgPeW? znFtj6gGJBM^z}(@iMasA6gYfxI1?OFH!-fF%AWm$|6V~HwIpPDVHg~)am;%Z!26_% ztHt84AK3WvDK>Y>vvN>{?Z8y!()r_&Y5>-Q?|~VrpS?=$5D0VuC>YEjc?*EXU6+w` zPJ#R&k)oZgVM_TaxUn?W85u$2+VgZsJLY2DLJ&ZWHEyb~bfNAm)WN06l9Nf1!N6l+c48oH_To*p?u9=VQ%t?t z*0;ZJ`**xBE1H0s+8Q0b(VnuUV z*)gCCpb@jk*MuhAv=88I$BK`shvPjkCrEJM@JibiSXyL~^OnCTXHHDYsEY&iG5<(d zY=7@>B|io5lgxnmqMnd3;rC#=cW?QT<{!z(IBguI8ZrgozU>5a1gGKU8^2*VtDZc( z-Hz^kSJL$8$1}5$$~c9W9S(|t&sp=<>-jLbpsp9`a=*FkYg2L7rCklrdHKRgd++D} zmj@t$c=LcfdH)()_jEAZNPO`HSi1HrR$MyH4uATNojJZ!XQE4J_@0`vgp+&ysbq}S zzT}cV`Rg7`2{qPdXf?z2_-|U`U@8Pqhk+kEwoER?v;sn=N;@EuHfp0HWra_+iG3`{ z-d^EJOzg(NVt&4j8$U@t2{^fHKYDOqvic1#{h1N~IM4q2AO8;}#zLYoeJ=U`%Ctv3 zj^~fbk^w#Rz@;?^ty`!&XW!G#SWuu=Fa<@$w(6O0T3yp}`}CuKwll|fxCCD1bk+J( zpHJUiq}Z(6-zBi<_D#-7cZMQ4re`we9Oti-pgOiW^BI=QCOgBQ*N=kA4I) zg2i}-g@1=_ppO0Omup>@bns)M5wdT|`itQ{PFjY?OzwXiYy`xkKcgd%aRlOZ z88}D6{!OlxWNcDZgI&9NUWXgfGqUBb-38#xH;4~yU^4X%^D#N{P#8t(J&@LMXb?0} z_)kq%kc~NsRtBl5|Fd+Ph?LyXnGfWNiNVAIX;|CYBX(rpdt%hMB7r%Q#f@M5H&$LT z&Ca*%Rb3%T8+XY0+J?06cOaDSt(aV`K7wWCQ|$WHHamS{r?q3|qK4gWEC{Y=%v!Ei z6xX}kRmTTI=nQ9^iH2PD0?>wO>g|zacHXiVt*Lpff+|`aU~uDrM9M59{g6$ejv)1e zb;EIT_M(j%eVbHYn{d<`pR1=PvWSMT_N%?>Ei z1D2#f7{36Tl1`@)2phakE-uMxY<^0>0oIM5eILJWJKq0$v7<1k)Ok`zcj(i%oy3cG zU07sI^Vh5Xlzw^C$hG29E8`t6jU5cM4t2Xo1B(t^>q!A6{@LTLE8H4#$$*N=YHLz$ z?QCnmaKaAmep~N-`TEzi7LiR?*Uz_t{31OY?O6bUG`9x)7LP4cFEb2_xE7K)fYE_Z z-mp7LhNR4IvOZQA4-XcpmxP_KYg%fZmq@z2p`b5rj1wgpG)+=9klGu9L6w*JHqKkC zKB9o&J==et5iACY`irmqdnJ`H3!&}6{*Qm*`}U<|F#)`Jx-=aO`x>~iaT9IPnpd4e zXX{bh_sOr^_vYuPz+!wr!WcLT*8PodLDL`DhJ=}81TowR#yHell31caJ++PWa3qPu zd%=+zB?4oKWEGZ)Jwe7U8QooTa0VUfTpg*;$G{>k#^cK;+xUr7mF(c0AaVE7H~&|w zYh0%1{P4}cu}`=DRK0C8nU+Pj^@M=M=u9v(%vz{LC-L<0dw*}&uU(3a#CUfP?%h>l z6=2L<*#6EB1d3hVd7m7yS8Vu({(aj!-fGDP5Ay~F zJMihSpKaykRSJq*Pww(E zJr~p_f5P~Lu~V2?P++wUi)_xqXA}%mN5~<~c=z-G@Z-UJXrbV0n^Qk7K#mdu1qIqe zU_f9?sX^iJ2Ph&ZbZrwb#-Tp3e;bSpH=a>J(eL^ESTPrAIZ|EQtan1YkFD=~->!FE zl5Ba>w3)Vi{lAcmchAtrM{LrJFMG}?)j~Zi2$>~ofjEDG-oHjsM-_%gSS?0!r0hNJ;Z9LYxJ8_630VenZc$v_go?eF9}+Wh zu*jULpS?o;63?GLV0*XyJk4+|tb5ky>Sw-fOV_=oRyx#1Z+ZQ%6j+CZYQOr(0PMu} zIcAa1!ssA_y@Y#PWVvb$nj{0bx z_u|=u`fqB#H@y6Bq;@#hvR}1|^v{**s{f{z`jaORETU>y_k};v9`fO@zbke)zrec- z`={ZIpw&|A@!ht2>(5-`Q}W^-Ii@aK_f@NzxzIj(^KTRfrmdqVEfyOVSafKSvJR4p zfJPENr;gx)N}YZV^EgV_WcDY>ZPI2+yQKf-pld(3FB<*S=m-ot0{y^Z0A|#W5R4KW zqv2Zkan^reZfB=(% zv&VK?%h8Y3d>gPq@T0gT*wu%*;{jt@s{qfc07Ni?sB2uJrh!)PKDk&s@6$S}*wCfe!aJ0wv>G8;9p&$0&GA7=&+If2FaGr+WZ zAmSJ>5)f|nL>{R=sKPv|p?R$ghguH8bRXB8Eh-wLb|=V*IXjvbtdp4#z>RlI+Zpv3 zEh?6*ngIPu+bO%H+S)ERKSN)|!15+#qp^DqwW-`|RqY&Gyy_JxV`z1OvLN)Yj8;zs zo>E{jj2}UC8d$u4Up2hTHoPVlI1^Z;c9^l)_@zIW-1vHDn|<)>zqZpyK1pju5!EOL zxo83`O8VQ|D<+m_U=AZuZaK1D>`ydj2LpF=R=DaHRQHm!cXZGZdwlGKvW2u|I&hp%}0 z>w50J+kPSUVb&&lIekiD7-8FJ!^Ge1-|>cO=c9N0q`lwaf<+AMrq-+PF7uySUCyFt z?F~?S8tOx3B9&~Hm1Fp(nr31HoUwCR<2hb;^kYxx2#iQ_;o&}8UTwo-cQW|NPjE?a zMQzvkJ0X{(<3mfi!Bz4u@Lf9=xQBle(&VAIK72~05rA}P0P z^FOKo*`igi%1nYbCe$h3z11!GU)=mAE0`TqmJek`3PJQEN;_P>x{;a|S~j zm}rcGcsDR#tu1@3u%Jj|N&VBjrO&A^B;bj&0|_6jt}}T_DMlDe)`FZpc@16`8r@^2 zv5!4K9Du=qEn0&caGio$8FJj}cJ;)1UoK%3{dfF*`hSln5j0nNdTe^bLb1RA+T9=h zBu$3OyTlv@a4~Iqvl!AHoBzpnfB0j8rfdK&lA@+Pi&@$DiITkH2z>eC2|KX!*HRhy z;$(d~?1O_P0>bA~UlEwouur8J`;6C&HJJ}AF#peUb+q^a)Mpgv+WKS6(T0^7hSc z+ws9aNC^>Q$j`!~J&Z9*dryPyeX%kT&WyUIB{re5M*CP>>rt_&nUd7;`;O8qn1c27 z=)4*1cQQS9IP-_|yANX=N3Z!XN5H8_;_m4W^V^1d?F3k)3Gx^LMK(+_h6Dv{j>t>^ zjF_Cc1vuLGWw?Vr`g@;!1SDMyfviY@0-G>tnw%za=0w5<=t6$xWF!7Oi+Xvc?jgBgYL;a=#CO@Vr z37MA}dbThmQzOHV_%jC3l)S-A88c5z1>+kz^vzkVzF%ybFeqnF?3N=dL8deCNYAgj zfYpOVFF{QY?%f8=VO`s>R8qv^;xd60?B6k%iPsdWR?(XS#X(2LgFKd1&IT44!}-fz zwAIi3kpk-5H?P{ZxBu3T?SEf;YG`;4dxX2}il@INi5~$ej1B*^pFeI#_r9m5=}w+` zw?B(LjHQ%QVCw;JV4R%9($~H!=yEJ0tvqHed|KxQ&vyFQE}6%WaA15HbJ#?Z0MxvZ zyupnWMn29e`=UCnCHKBV?NDX~LELmEJ_OtuHSS1aF=)AV^@8pHO>(i+rAq zH8FSbCTm)-L2_m4HtB;G)@ic8WcdAT(;=uA;(xE6m_DeD2c=Q6hYu%|7XcKw+Rk1{ zw@K1fR8F&s$#pU~qNba%pbnaZ*ZG!xcJk0ilJey=_l7a2hx;qhIpQ8n@Vj#I3?<4i z)_eYI|6Y=R0M+I`9@WhWjngQ$J~}nje(7(tz=29g>8A(WhT6{UkXP07y7Q z)B1>W=-{q5W0GyB5CK%8{#d#3n=*Mixa-$a3WT4>@qPzVQuI^4bgF%>DKXHf@|ae5Y(fDFkn_en27fHLhPU}XSY&KSq@ys__f2>{0`W@2mu zYgF5?SnjMa1Ju94SOV76A|tp*#-*oTdYKaW`gR`!O?vJ_VA+8YfFK4v&wk~9kXaDH z#-6P|wcQ{7#O@g-Wo-@= zz(hfcXWs%KaCK?BEmsd>fp8sD6%;V3PwwC)$%sh34%}bxtd3D4)hpK+n%V_m(y#dZZiGg@s zp$i0iRg(!Iq=n5+z+#Z0=jGX~dFyQBD}OGA_|}as`|!>0D)Et;Ybo|F{tN*u(oYda zi~FR1>*Cd4wlQN%?8x5tWHJRH5B0%uBc9~7GU+272=^i)&&JEZC((m11ibxavi*%~ zU`}w)WSk3&i#0cJw1o*J;aom(s>TATH+v5)i|jnrEpMU+&X*E~b)eeo{Cw56vX1X#L>4o48_F||g2kbX)}#4scqb17*gcGE zj`XPH)ix|q&K`hRHLXcf66zJniXgSYu}*!=QnbQI-$TahW!eaGTj-DE_C~+tF^@nT zEQa88!OAZxGa48k<3c6 zQ?lv`d`8 zO;0RbNy!FNm(p@*n=`>d@+sqv3^LLzl1hEp1I7UXW)d6@02ZA^e}P(9044y(4j{c3 z)xapG?+FTq1hW|3QwFf;!3xq|3~e~faW*`*f3xZVO+m7g-=%^@AM6RRq<(^FNw(>( zx#P!;u>}}lPDE=H0y6HJ{)t=O{H}msF!@LYm#!yg^U@crY5qC|8_4$#eDb=ae4zTThwm&GKVJH6kID-q%3Xl{-& zp82ZvTJqFat+23AtTz2TVf$gVLdz3LTLY^bSY&VXlB&Z^C1a9zAK1vA`}ehG=^u)O z_sogiVom@nyraOFyLaZUHzcrVeR2pESZr^#U7LR-1ptFmKB3B<{?eaY{oK{sXAbRr z(>{6sAH)i$F^Yb2_1lBI;sM}QI=;e|t$R(+LQl$rw9V-_Z$*X0t|g9V_2T1@#vCTr zo!cK$V3F1*m=Z}9k!E<~uIQGAYqQ~&SupfSpILHF^|h7x-Z@q!D%PjEYh>lK7i^HM z`t;GAVw8iKQGEY-oIoqdqVnv3Mf@6&V@|7?BapCb^ABz3hd*}7t4yj9zaKs3V{yP( zN@r$YpAu3TDkz(37N{(X>pCxV-E0xS+P3ieiCqExw=g6>~3~fT<}j9XHV) zJh-cUfkX*F8d>&`ezKjLL%PW5hevt@++OL-{Gxqvgudi+0T$~Tm-XSsM<$RgKR*OD zm#9zdzM`yQw7lY(vurHH2oGNTa*uK&8llG+z05-zfv~tj5QID$hc^2Aakvv`li?UdA~Uo7>pLQ{2vaAh^NR5!o5nb-_CUG#2xY1xPyoWqRZ&ILssSSf=_! zf+?)H5AS);HMyrXM1U$`V~QD!xIiuiWuls^l*U$v6>S<|K)8SE-7u=5^#GY;=NjsQ z2905S9VZh)@&As4#kk~ju-{MHC!Exd@p880i)_|{^|}xGF}9sMrk;}VHXCVRE;g_} zj7`hthy4K{sy=p=eP#?`xxSWpa)jOZ z#eXa5Z&6W+ojbkPHoyMYdM*qi;$YGBs5Bc}I$m{un7}Y^5A1kDj5v&=E8BCuGqcqw zjyPEKfv@u?@(GcA%#BJ00?df84L-EK$ryyr9U1ujb;n`6;)#F@n~w>`Lv0<|=^Vkeg_EvvAFYhF>UJz$Pz z;sn5~RXtJ$$}O3M84NsP{v_wx?hY}Fw{LcddBQPs<jB9-$0eN+cBWbnth{oXT9(i!7E=`z69S9goF`I3IQKfYE*}FkmkBIl z-ZOvM^R{5sD`Iomqu>7Vf3z!YE$RDB>|J9Xw2mzLXu^o2zHZ9_Oy|W+ipva^1EXgoP7WNMkpCs5yO3MYzS;x8mgg&SttJGhH zpZm2&KRJ>kkeqLia;}f$a}4)dd8;>lr;i58uCZ>Pm_%F>>7N*drVkkyX1n?LL7wff zAMS&X{@&+*1Y9;fl`*Hi%j#$U&~S7+yytC$X_&QOot2KCEXIx^b)5RTyV_mNS{!`j z(X72l&8P{22>|&FZDOuoY4uVY4>5dZKRP_J1UZqJj;DnPiK=R6`}P&J>P1I`a%!5~ z#zXMj9}LFl{y<={bo@l45qRCq#cH69kqd1#2;K?cqE-M=#GUyda^Ep5ek$XnN(JB! zEJ}VmXO-2~FVvw*YYZ5e){~zq=q&QBNurA-WM9#EB*xv1VV+gbm}j#WJ}nS-{`5gR zbL5uE}U7#q`8ksU%R$wyNW@+VGhH z->}baGiH2_wE;LNub3(z3>d%G*`}U!}X#Txw)3;TN8W{Pub4O*;;v6zX z8>b}3F|dAIjaQ_4}9_~yL_?5^-;~#J2f%G2c84|4*JX{S2w87 z9Lk%WTmDHVAFvSXzVNSY($ogEBG~%&e^u{O*X+DMlaVRN5aaXUo=vM?U<;PNXk$w! zsLs#HSiQ_I0@gxvX|Fm;nq~Irj6NG$>cr)sab-es{%H35xsbYV$5b+|DRo6^R>8JV zD^1NM>!6@$j1(TU;fc$?b!{ZzBqF?o`%#}t$>ab@9~id{Fa4=iOsQ3%zhg5!GJmP_ zM74^s1m0lEgGc>51AU)M5Mrd^ovrf<#8mT+n&v+xg$K{)YBB?Z(q~0QWA(&0u3fRN z&hx4#r{Aa4CUVp5FHwFJ&z;;S2HOjBInmh1D<;(lK=WMqb(}rn&ZV#yrjE~$uyOk% zY&zhYy@3Q(ex7SHHKd=I3D0oA@Q}W1^uwbgFoY4vd+D41p^rturigI|8F1Ja79Jb; z#AooE5JiWa)rKO9p}{xFP&8PhpxsgWuB9H82ePuKofG9BLb*#^Yqpy=u35{Gtu}7_B)f9?wDuoox8wZ zWU7P9FYkdGUNYr#m%U(A1X$~ftw(eLY6Sy$AV8x1$;yr2vi7!<)^cd8&78Z+ zI@`|)Ffix!D6#srOz$Ea6BvIm$+hzftbW!Co3r?7898BML~E1>kppSwHJUAW?6*c@ ztZwC$8Mfl-Z^*0#gPYh3=fKW4+}!n&+!PDzP*%(J001BWNkl5b-;7)i&r13DfDVC)AL3kviO)=;Zh zR4g^h`>+2$QkNu?4sN~l+p>qe?jF@I1c2`~;!Y9c-(f@Z8e96**K{tyWYbTPzPv~* zZ*_Od1Ay2N5&^bMZK(QOk}S;UT)@~!KI>4yqC2ez-Z&vma6GPm&-bncUG}+kzjLk@W-{^HdpCb?li!N@#`O?Y3>SwRAlLxm*!o}v#p+B*z z&So^a-i!P)&vblez?fzcM<$F`% z8aa0CI7xg??B8PDU2Xa_uB%avQ0y#A9XSJo#mcEOZSJCHRAV{W zdyMfDCfmg`hwbpE??^7FrqhY{5}@NyX1|^zCYy9^CEVPrpR>v~zVv5SURkZ0wY}Sa zVY@!~p?VEQKb{3wU|djSP4m`TWAi%I2Aw~>Pk`ro_Z9o}!=K3HD12911RNWFM%UQmdYryq`TE z{mhycZm`vxzAaXn@80spcU8~j^}{}y6p5z&dhZ{w5}aeq(=>m*_4Pim;|D%eLW>${ zw@1WenwoQtmBmyB&?Pgdz8)umQ!S!vxx=5s95E;Lyy}R8gx-P0WWY^w2~`D>_@o&P za~2aS-ZOE6z!R)DbDSQmzJ6==!i{1UX|n~(LhU8&`k`HKDItP<4`9ge-SoXQc|MsZ z=@y5V2}#bAT(0Bx6b~cv^Q~fHjct78-`cd=X3f!^AN-?g^8%=igY;akpTlx{WFK*0 z(Y{&9+-CPo( z+1^=@f#YOa*SO4zOG>3Cf<>j)Kil&$7W80d4$)&a^c7`{Subvp<#zri*Wx1`%+W6! z9f3hcAaDK4f7(ZV4D~!ZfHJtFJ<3t+-{;I9lo<}TM|oeP-}PjTKoUrWBm+PZ>u-A6 z?cDrB)!%X;63msAS6X%5JZqfyl1pv%aw{_;kF1vq+9*T~k3@s!wjd1+>>C8`__4YlGWOl*wmu%dG zD%DkDB679;tOvOsC_aW-pyacZj;mCAkV#W#Dv+nn4e4oBb(7u!4cO_mC~y_bNB~v- zm=3{#JM2AECKvG~w!}kk-<>gD})V%b0%>in;ka8m1gmv4!<;NNi zSFaeVD-$&=NeS*C0d_8dR2Y*uScFkThDLoY20Yvktw*SX1yJz!LH-M4#QR(A`g&8v}dPx#I_v)C_tpDEel*Ccg{j3ez0kaHj2{kF_t z(t@-R8Y_SiN(I0o=2_=X?YEWBe9Nk;XNgJt=&k>%B$aBJ;-JSH>O^v8KN+HWxx9Rv zGJUo!TKTf%yD&Sf3I1WNFkc*4lqS^IOZRH7Pnc9~Ww_3wAn56lITCZp?RiC3UQwmi zE&Lhv*8u7}x2|b!rUl&WRRx7cP3E}rNn+)1b$57OL!THXdPt7vTAgjy(bf{}U#I}a zmQ`5Aq-v|GnWJDE&&>;G_A5?Ca(?#Y9yyAV7-BExFPQ7px=Otv_hY9%7%sy&EU>7( z#>Mk;C0_S6ITHhlsX6`aFaFXxE}u@@EdiaoN;oad^vF^n`Q7z(*-~OE> z`xzBwk(}Gt)yW~%_qol1wHxUOVkE&;NX(J!qm>mVaM!POSnJ8%E-^CT^QCHeo%x;H ztIH==*}c1Wlw8Z@Cwd;w_~!CEqn{Zafk!n0d5!a)>cgEbk|_9Z9!hXAqBk35Ve*uP zBy*!IyAPZm+kK7bLk{6$84N;(@Y@4_G{~fem&hHl+ZgtRLLlv*gG}}0X-&3rXHe>b*^-pxo>mP`LqFxtP0I)?M6Qo>edBH68Pth~@dm&JR z!KD5L2_B$<0GptRU@bVECJ*II;4oZU*?1*%@~m)7u~k*iR;>v&$8D`gWFA5$pP;;- zo1sp-9A9)Y6PoMqC0?YH2fq`Oa|@XITQ;OXrX3`g{*Rvhz_i=v_`jX1(8}i%Au;W`eyzPq?eR zd^zTAc?K%~ z>8UgK!7_gNhHqHYyr)zzyJy=^6)2G?ShnFcD=ZjepKkrB6fCeBjvaG=IPLsN-d~ny zXRMIV&6u@P-*e)?W@|ft%rRX_Mtqr!`^e`(|483g4wuo>6CgEIx`>#7M+{rSOvA*6LpdgdhSW~ ziE^Rq%6Yrq-EP#wR!(iO+c!GZWSykcl$zOkr_?fsa+44US60omsncian)J}4MvXZ@ z-%4C>nXe^f&+b=NvC$VD=hkm)bU&-IlJ>2s09*d(8Q?yLWk%*}YV-5>tg_I~^e zv9)PG!`u&tbYCO=;SBp;IN#{E)&D2`CbnckWlk^rpgWQc+f43%ZWM+*;N#}unHS#rZC*JQ}oI9+S zJo-zIas={f>KFFKnT^LjNn>Rm<14BpiRtRR5arE79nGU0q>=fqAORUd(C#9sEMK2P zaG34JeNdP(Xc?I&e6&|dji&=#)OYnLFvYEqtloj0Z>q_8FkuL+H9=VAlsd^F2@J@V zGtSgyoI1Q++4;~e#w97@g(+To82%_xQx|He#+H@~z#z%PC>( zz!(5RVR`^a+%J91x;ihqW5!F&;;lE*WNd@Is7zpSP_UA?sOs&U4gIY7>lAEW>$+qu zN48l<+i5GCFv%uPs#P5ftW1yr(G0sFzbK|0j2lY0ur~Z<=toDOLqL16^^l!7@S$pK zRO9D+gGIGQgFQn`Vj4h9+^sVHg#3BQxJp~~%(oP1A$Nw&-u%X239!Iu#xvglDv}b@ z>gKBlAmEVRT{!KLn1F3ry7tRzVMJ{g0dz!24Y&`)?rN|gHavg4_KZJEbNO@ZDU2cO zYD#sJOrq$Sh$M>^FD{sL^-h77;r{7oxn#|&)_M7?ef-|vSy#t-1zH#l!S++v1GA_m z^Oc7uNl=8bSsYF6& zlD-dilHZ|LFUarMQ=NRYM=TWW5@0>K9ISZ z_V<7Bmxd|Rpzm|A{q%AFeJrUOua{MumT?np?eqWAIIli__rK{Z(JnjKUJ{-u(S!GK zKk9&zPvNjY>pMv1{!^<+m)jUxVZJC;uR2ll$KZ8toa+{%8Aj*nPWTc z!r22lfZ~n8Gs$QM1B(RTb&ZRye(o9@TU;i|CD*5MFttvpx)jgM`TCNa5C37jtE9<; z>VWbJ#2n0C{EQmYUp{|ab#6DVT~;jztO!A8SI4=CRTOCO627$ChzOCY1|d++61^U{BrCnu-hL*igD zW^@t(V_3z$UYlIqWOEj65|Frj?wB3j|AF1Q-kEMZ5dy?vhQCRnpP`SK%AiJKU@G z46a-6J~`)GqGa4La{`O5B?Rmppm=J{Y^$ERK;O4>%Mb0)&bP$)Mc)^H8Ck(%sJDDc z$rIX3Feh-`L=sP;slBbmfo`89aS4Px)oCIxZNGTJ_2Z{p&p@37?;*IWhxicffzjWcabzW}OcdFN^V?<-XF1y5zk5rL#3)nl-n!A>!RB*yPNovhQQY9!d=e|Q zjmvDshSvlVcW?QLN(0=I$sAi`{PQPiJO)Y#2C0T;=+lw_d3j18!;Ay+Zd_}(bEo&Y z7%8>+XFftS$6P$%=C5fT6c&xOyLVi#%B(-3jy;jUlZ*2pr3HhYXQLk&9f1)XfxPK6 z7kR=yQ4=$QUow@r3a;bgvUqQ`d?aYPNxL||8KKHgon0JLY?1@{WU9Nx1inwM3a_W@2Jy z+i#M8E(Wc)M|Eq|Z&CBsak7U2SvB9r9ufP2^T<25?)w=?`tfq#E0|{a1E) z&s#EPVO(JxY3RLh^((q2#y|1?gWP%mi^;uGf0vMf0w_w$CW@U!eth-nMX~CgfDLa} zk~T(Bdz0+$p9AiDs!PS#10Z7pzH^p5YqgC_t*WNU&b92b?eBcwH7DnW15nL0+2Y9v z5)NZZr9PNBd!=NU0BO!T_9!HuGn$s`&#$ymGv}nbA+b+k4;IFP;*xlp#oO zkM;=GMW_#cSm%=FiEpgFaMhP=)id8#U&XE~7vzA-81&ompCn+E=($2U@s05@2!=yJq5_zn`qZUC4N5$l@vJ?(3Cl2{JyiT*~rtkg6WXkApwBhPtT) z_9nQ}{jPvT2NZg(Vp6Rwd+Mt?_&(kG&r$svfdBywO_#~S!y=NkN9K%0J?vu5%!LYw zN=hfl5Q0O4Ku1zA-^w7=qD8Y&a>snDm{MnrbJo~|$u)NE$^|=qXp82qYs%|DPU>9+ z!wN6ubCIzwnaTir(3fXcQc`X+n^#-)j0FndXf#j#7(rif5zNFuxu9!g*G&?Trd^#R z57N_x8&w13+E=`9cW>X4D=FX#pa)|@VC)Q1QfoUfM@}Nt|HgUNDK)dKv3a$PpHL-G z597tP!uV><#eOveg}H#mtiguo_W6$5hQ+q-3x8r0DyyyM{$1O@;|<&Q@vl-fU_K!v zTX{3}?wqx7gH=>gTY5;n6hk|YFsBIY=Pr3p?N#XQMPE7?7mQS#<7AHl`ds!C7we^u zT_#W%9}nG!pM!vcSqnDGLY{Ue$M(K2pvY%1APRD5_GC&07OZ&58s@GQb4+UtSXOrr zIB|}#qA|rbf8`f#Qq>IGyZx8ee&KlkcN;TSOAF*;Yl3IMcmx2_*!+}CRF3Zbtt6MM z)wG|mzj}6YAdo%K{s}`~I=;g0-MMY|?%a?YEXkna;!-IHcD(-&)_QWU_4PfF&1-i5o=cQ599#qWGxfE1?%cGt*28iRo;Z1ifFiY|Ftvb3WTEVha=7(l ziJ1^%f1|72E?;zkH1|?7V}a&3<~65}@3xC)4hVFT5UQ?Us3ZY0;hWu^lHIZ&GFA$v zZ(rB*!C2$IseX3Mbtyr755F7%TJjxdd#`Dq>+6$T_nBA!LaY+!D~X)#zx_MAd#l?k z9a8)DP|wCAiP8)trUe`J3p zF^^L>i53#Otta*chE!KbQ!NCQ%>J-JyR%^VeK6>%;l#hw?kgEL8ZC z7+CE0y)jnu4>~rQAl>Q5ybgN60!W8YoA6KuXXG!+ z`~Z-weEJ(!GH#+B-1&xGIDOEYG*sK9X^qMrv$@k#iol%UgabuAk}O}Ye_|P@H7J|j z-FZnF{0nCeDY%I;g|S*FKqzd-xCv7QV##8~Y3z7MP&lc*jT#RsmRqEDI-(9=(me|QHwHvgmcYS-V;J-?cM7Zlmt zrO#VU{d~;_L8CD*lahiby{ID23$?nfLz|Q|I{r~---E7=*LJx^y=lazP{Bpf_F(w_N|9x zo)Wzu*G!$ZD=XH2-3p7xiZw-k3UH6wulN=u!`(ZdnBR-73;HBtL^W^ui*~+cuN~a| zmJ(ml&k)wh6Z3rW*vkKVX#ay`8&G%WR%Tf!B`GB8V7!sya>lA{R$4u`GxI{(fLaM) zdH41W{X2;ghL?59UOBX%ppQ-L9Yedw=%+_V;GvE{8d%IFfPJWU6FX=*Fe#Ylu!LEQ z9I0{*iXQrn=J*BuBnue~YvLPo$fWx~k`0MIK4f*t(%-vx%kJE|Vb{AZMKy;GG`j1G zT?v`0&+~?#$$5l)=>+Q3fH?P{sgCEJPK_(x4CRb7zqxv~31u|hdIB4i8mzSwdD*3Jx z(zGbp^vq1jxCu6U!A7g9ZPsB&piMuwyLWD-8H~7>??)pGAjrk?eONWYeWsv`Of@$7 z03_TNk00FPSyfnqJ~1BDS^=6OY4sohVPM`^|Cql}r&cksTE;jyZi?}W*x2A0*?)~? z1&hfElwmCra1fx68$a3Bz5FLOy?&8^5OtW_-u;0yg$VNUu!ot+OaucKTrRt=w2HCl zzSf?qZIg5fhss&jyl9hThNqA1)E!mV%@xZ7K!Ek3PaQ$JGb*8vUaHQ|^U-PY;{n;< z@XUHvC!YfNnT~N1Ol~d#}9s}_2Ci>e!}{7l8G4)^O5H*DJ=nG2%Pt~<|WTLgO)3;>Zb@el`Iwu zf4=}SJ$p{$k#Hdl22sc(Crz1Q3s${sHT8@1-MA+691cj|?-x|Yr&TJ^qRAm9al!I0 zC=rOYKJ$oo+<6&Lc+dKJdX(Iv4wSQxKgayW88$ijFSUts|2=n9U|CXTvF=R*kr?A} zUhwZY10zKhvsf}t?~MSLu|tke5&$-ZcV0MVjEyUwBGA-vsl~eGD(vdRxhKHlwazvr zg7`z)#w=Lz1wGTjUB6KR&IQYPHm$DN<}Z6u21i#eozcEU;_kr%=QK@w74}z>N!)Kx zyu{T-!#V~M$%5z_F{X(z$CxWl{_Tv+ko5B7*3lqR-k760%sgkC4E17XhY#i+`qUWxg3%Gk zbp-ON>*i&%+sySEBl@|(F6cm%^IC^%tQ{J`e$L8%lT1vUp~-5g9_r3~Fo*1c&7Bqm z1PC0&7QS+vNr+7jTgEfE!>F9?=&*LKh1Gvo6=$XVvxdWk=t2<)Q*@ z+)?QlM@AiaRmbJC3UYZLY}k=mbqsW?9YD!AtFCL7Aq#94bvM-DQ7?#;uyOuVlCAdj z^jd4nr*{7I0lUSaq+mJspGbb`-y7=y(1q-6THRc`bMv~LI`**wOXt+eEypsF?sUl@ zfy?w~x!zZB+znDLM@2ww|;YHVI3#^?N*1I}#b_I2;7*()};X67R6?zmvru3nae z&`r~UTzvz}*yoHzmcF1~ZZICy*R-paD+W43kdXEcInSMZFMb%O&6n741O_-IIqnnd z3|mcI9yMkFCxYm0Z-37&oH-b=XbuXv>@bpM%x^FbxpD219pAr2Nd`W_^#Z_^q!#w2 zv|NdRGbeT{*oIA>RyRihH+3|C#LkX$djHhtku;L*Iu5!L^{GA3M8@)qBbkhN*-{M$M?o$ zeQaps;%er&bb&R_TVrdU`&R;BfOc5Ll?ACu@#?8x&Y)tQm?*gxy@R<(P&wP z0znPm&17n%fVQ{SyNk|}fek$pLn|CPE7G#1e6kE;_&X%>1o}wpNlXCh0hwjxlWg4h zN^5UBWw&p3>3fh))06c2)i#xQ&>vA!aIwIJ0`^=RB@5sVCPr()8{x3mk?cVtJ+`D= ztQA>rB?yZ`_M9Z5t%RJkBfTTmzyAl@134C)wpmdh7g)XIao%bK2AJ4av_ zLmohK%uQrS`{%$fJALirCRbU{Plr3+Qi=GQCR?)R%Q9fYkcz!p<}A_krS|$K<;kM^Pg`fvuA8=t z2LmnMAFLm>wEaMwCmuMnW;8CdqOm24r6`@?{ipqSfX9ATT0TjCpymaSAnaN%>fivE>)2uBBnlYB{H}snaX$_N^{uBgxvg zp4_JzAjt)Db>9r&#s?oEQ3Cr(P&ae#Y6XNi@=@~xn}IYY-qvHVSNqxiJ}z%fHya6c zP=G)HPt&}00@i@&Q-`Pdx(CrX5)jCWxgBx<~25XO1)j} zXtfguw^~={`3RgurZ!>DCNt1+hsDI0C&wp}hvw%;uBK#-VS;G?Kwv?_V9)lS*@^vI zq9jeYju^1A2?9nKupqeu*j~AOM!`Vyk#$FZ)rXGsaQqHNcoK1Q8B)8Qf+|k(sf_8 z`dKSfr+8@BZ`5BfwV$OY07(4t{&-f{xZ?-5^b5oyP?}-FiZQEhwAqWEk<%yaV^N#rq#{UoIq{~y9TovOk$izsjK@;q*S7MWsv8D ziPd7;$|h9Wxl{Y4RKPR`862`u$(b>oscF*uzH+I>?%lp=<(1PER3g15nLr&VQdY+H z#20fA;m*`0^ Date: Fri, 26 Feb 2021 16:40:58 +0900 Subject: [PATCH 088/851] [autoware_launch]: Fix missing arguments (#66) Signed-off-by: Autoware Co-authored-by: Autoware --- autoware_launch/launch/autoware.launch.xml | 2 ++ autoware_launch/launch/logging_simulator.launch.xml | 2 ++ 2 files changed, 4 insertions(+) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 6aa26e6b83..e168f65b24 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -31,6 +31,8 @@ + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index fffe483a5d..c05c32b786 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -42,6 +42,8 @@ + + From dd862c043437860561825ae90ca7da47471cd9c0 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Mon, 1 Mar 2021 11:10:18 +0900 Subject: [PATCH 089/851] Ros2 update v0.9.0 (#67) * Add pose history into rviz config Signed-off-by: wep21 * add blocked by obstacle option (#164) * fix tab name (#166) * disenable ndt visualization (#169) * disenable ndt visualization * change alpha * dont visualize position covariance Signed-off-by: wep21 * change global frame to map (#171) * add param (#156) Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Co-authored-by: Taichi Higashide Co-authored-by: Yukihiro Saito Co-authored-by: tkimura4 --- autoware_launch/rviz/autoware.rviz | 65 ++++++++++++++++--- .../velocity_controller.param.yaml | 1 + .../behavior_planning.launch.xml | 1 + 3 files changed, 58 insertions(+), 9 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index b59a1d7f03..3a75dca8db 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -522,7 +522,7 @@ Visualization Manager: Scale: 1 Value: true Value: true - Enabled: true + Enabled: false Head Length: 0.4000000059604645 Head Radius: 0.6000000238418579 Name: PoseWithCovInitial @@ -556,7 +556,7 @@ Visualization Manager: Scale: 1 Value: true Value: true - Enabled: true + Enabled: false Head Length: 0.4000000059604645 Head Radius: 0.6000000238418579 Name: PoseWithCovAligned @@ -570,6 +570,22 @@ Visualization Manager: Reliability Policy: Reliable Value: /localization/pose_estimator/pose_with_covariance Value: true + - Buffer Size: 200 + Class: rviz_plugins::PoseHistory + Enabled: false + Line: + Color: 170; 255; 127 + Value: true + Width: 0.10000000149011612 + Alpha: 0.999 + Name: PoseHistory + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/pose + Value: true - Alpha: 0.999 Autocompute Intensity Bounds: true Autocompute Value Bounds: @@ -651,7 +667,23 @@ Visualization Manager: Enabled: true Name: NDT - Class: rviz_common/Group - Displays: ~ + Displays: + - Buffer Size: 1000 + Class: rviz_plugins::PoseHistory + Enabled: true + Line: + Color: 0; 255; 255 + Value: true + Width: 0.10000000149011612 + Alpha: 0.999 + Name: PoseHistory + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_twist_fusion_filter/pose + Value: true Enabled: true Name: EKF Enabled: true @@ -664,7 +696,12 @@ Visualization Manager: Enabled: true Name: DynamicObjects Namespaces: - {} + label: true + path: false + path confidence: true + position covariance: true + shape: true + twist: true Topic: Depth: 5 Durability Policy: Volatile @@ -680,7 +717,12 @@ Visualization Manager: Enabled: true Name: DynamicObjects Namespaces: - {} + label: true + path: false + path confidence: true + position covariance: true + shape: true + twist: true Topic: Depth: 5 Durability Policy: Volatile @@ -696,7 +738,12 @@ Visualization Manager: Enabled: true Name: DynamicObjects Namespaces: - {} + label: true + path: false + path confidence: true + position covariance: true + shape: true + twist: true Topic: Depth: 5 Durability Policy: Volatile @@ -713,7 +760,7 @@ Visualization Manager: Max Value: 1 Median window: 5 Min Value: 0 - Name: Image + Name: RecognitionResultOnImage Normalize Range: true Topic: Depth: 5 @@ -724,7 +771,7 @@ Visualization Manager: Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true - Name: Beam + Name: MapBasedDetectionResult Namespaces: {} Topic: @@ -1221,7 +1268,7 @@ Visualization Manager: Global Options: Background Color: 10; 10; 10 Default Light: true - Fixed Frame: viewer + Fixed Frame: map Frame Rate: 30 Name: root Tools: diff --git a/control_launch/config/velocity_controller/velocity_controller.param.yaml b/control_launch/config/velocity_controller/velocity_controller.param.yaml index e268548e5f..6688822503 100644 --- a/control_launch/config/velocity_controller/velocity_controller.param.yaml +++ b/control_launch/config/velocity_controller/velocity_controller.param.yaml @@ -42,6 +42,7 @@ # slope compensation enable_slope_compensation: true + use_trajectory_for_pitch_calculation: false max_pitch_rad: 0.1 min_pitch_rad: -0.1 lpf_pitch_gain: 0.95 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 7998409473..573a9b699b 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 @@ + From 7c3eae594884ef88e75d5760ec49c7afcebc14b8 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 2 Mar 2021 08:58:39 +0900 Subject: [PATCH 090/851] Sync with Ros2 v0.8.0 beta (#71) * update sensing launch to support aip_x1 (#69) Signed-off-by: taichiH * fix logging_simulator_bug (#68) Signed-off-by: taichiH * fix aip_x1 param (#70) Signed-off-by: taichiH Co-authored-by: Taichi Higashide --- .../launch/logging_simulator.launch.xml | 4 +- .../aip_x1/pointcloud_preprocessor.launch.py | 112 +++++++++++++++--- 2 files changed, 99 insertions(+), 17 deletions(-) diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index c05c32b786..67ba948c08 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -4,7 +4,7 @@ - + @@ -67,7 +67,7 @@ - + diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py index 19505e1d88..57f82c4a1c 100644 --- a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py @@ -24,6 +24,7 @@ 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: @@ -38,6 +39,7 @@ def get_vehicle_info(context): 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: @@ -45,7 +47,6 @@ def get_vehicle_mirror_info(context): return p - def launch_setup(context, *args, **kwargs): pkg = 'pointcloud_preprocessor' @@ -60,10 +61,10 @@ def launch_setup(context, *args, **kwargs): 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', + '/sensing/lidar/front_left/mirror_cropped/pointcloud', + '/sensing/lidar/front_right/mirror_cropped/pointcloud', + '/sensing/lidar/front_center/mirror_cropped/pointcloud'], + 'output_frame': LaunchConfiguration('base_frame'), 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }] ) @@ -78,7 +79,7 @@ def launch_setup(context, *args, **kwargs): ('output', 'concatenated/pointcloud'), ], parameters=[{ - 'output_frame': 'base_link', + 'output_frame': LaunchConfiguration('base_frame'), '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'), @@ -101,26 +102,28 @@ def launch_setup(context, *args, **kwargs): 'max_x': 100.0, 'min_y': -50.0, 'max_y': 50.0, - 'min_z': vehicle_info['min_height_offset'], + 'min_z': -0.5, '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( + ray_ground_filter_component = ComposableNode( package=pkg, plugin='pointcloud_preprocessor::RayGroundFilterComponent', name='ray_ground_filter', remappings=[ ('input', 'measurement_range_cropped/pointcloud'), - ('output', 'no_ground/pointcloud_with_outlier'), + ('output', 'rough/no_ground/pointcloud'), ], parameters=[{ - "initial_max_slope": 1.0, + "initial_max_slope": 10.0, "general_max_slope": 10.0, "local_max_slope": 10.0, - "min_height_threshold": 0.1, + "min_height_threshold": 0.3, + "radial_devider_angle": 1.0, + "concentric_devider_distance": 0.0, "use_vehicle_footprint": True, "min_x": vehicle_info['min_longitudinal_offset'], "max_x": vehicle_info['max_longitudinal_offset'], @@ -130,13 +133,87 @@ def launch_setup(context, *args, **kwargs): }] ) + short_height_obstacle_detection_area_filter_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='short_height_obstacle_detection_area_filter', + remappings=[ + ('input', 'front_center/mirror_cropped/pointcloud'), + ('output', 'short_height_obstacle_detection_area/pointcloud'), + ], + parameters=[{ + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': 0.0, + 'max_x': 15.6, # max_x: 14.0m + base_link2livox_front_center distance 1.6m + 'min_y': -4.0, + 'max_y': 4.0, + 'min_z': -0.5, + 'max_z': 0.5, + 'negative': False, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + vector_map_filter_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::Lanelet2MapFilterComponent', + name='vector_map_filter', + remappings=[ + ('input/pointcloud', 'short_height_obstacle_detection_area/pointcloud'), + ('input/vector_map', '/map/vector_map'), + ('output', 'vector_map_filtered/pointcloud'), + ], + parameters=[{ + 'voxel_size_x': 0.25, + 'voxel_size_y': 0.25, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + ransac_ground_filter_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RANSACGroundFilterComponent', + name='ransac_ground_filter', + remappings=[ + ('input', 'vector_map_filtered/pointcloud'), + ('output', 'short_height/no_ground/pointcloud'), + ], + parameters=[{ + 'outlier_threshold': 0.1, + 'min_points': 400, + 'min_inliers': 200, + 'max_iterations': 50, + 'height_threshold': 0.12, + 'plane_slope_threshold': 10.0, + 'voxel_size_x': 0.2, + 'voxel_size_y': 0.2, + 'voxel_size_z': 0.2, + 'debug': False, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + concat_no_ground_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', + name='concatenate_no_ground_data', + remappings=[('output', 'no_ground/concatenated/pointcloud')], + parameters=[{ + 'input_topics': ['/sensing/lidar/rough/no_ground/pointcloud', + '/sensing/lidar/short_height/no_ground/pointcloud'], + 'output_frame': LaunchConfiguration('base_frame'), + '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'), + ('input', 'no_ground/concatenated/pointcloud'), + ('output', 'voxel_grid_filtered/pointcloud'), ], parameters=[{ "input_frame": LaunchConfiguration('base_frame'), @@ -185,7 +262,7 @@ def launch_setup(context, *args, **kwargs): plugin='topic_tools::RelayNode', name='relay', parameters=[{ - "input_topic": "/sensing/lidar/top/rectified/pointcloud", + "input_topic": "/sensing/lidar/top/outlier_filtered/pointcloud", "output_topic": "/sensing/lidar/pointcloud", "type": "sensor_msgs/msg/PointCloud2", 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), @@ -200,7 +277,12 @@ def launch_setup(context, *args, **kwargs): executable='component_container', composable_node_descriptions=[ cropbox_component, - ground_component, + ray_ground_filter_component, + short_height_obstacle_detection_area_filter_component, + vector_map_filter_component, + ransac_ground_filter_component, + concat_no_ground_component, + voxel_grid_filter_component, relay_component, ], output='screen', From 3331f97d1ecc45a486b7b4512068c4e62e8e1577 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 2 Mar 2021 09:28:33 +0900 Subject: [PATCH 091/851] Fix aip_xx1's pointcloud_preprocessor.launch.py (#72) Signed-off-by: Kenji Miyake --- .../launch/aip_xx1/pointcloud_preprocessor.launch.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py index a13afd6504..3d84321720 100644 --- a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py @@ -61,7 +61,7 @@ def launch_setup(context, *args, **kwargs): 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', '/sensing/lidar/left/outlier_filtered/pointcloud', '/sensing/lidar/right/outlier_filtered/pointcloud'], - 'output_frame': 'base_link', + 'output_frame': LaunchConfiguration('base_frame'), 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }] ) @@ -75,7 +75,7 @@ def launch_setup(context, *args, **kwargs): ('output', 'concatenated/pointcloud'), ], parameters=[{ - 'output_frame': 'base_link', + 'output_frame': LaunchConfiguration('base_frame'), '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'), From aa241cfe37c6b700b31bef35adaefa0da43b0eff Mon Sep 17 00:00:00 2001 From: Taichi Higashide Date: Tue, 2 Mar 2021 16:48:43 +0900 Subject: [PATCH 092/851] fix velodyne launch (#73) * fix velodyne launch * fix bug * add scan_phase arg --- sensing_launch/launch/velodyne_VLP16.launch.xml | 6 ++++++ sensing_launch/launch/velodyne_VLP32C.launch.xml | 6 ++++++ sensing_launch/launch/velodyne_VLS128.launch.xml | 6 ++++++ sensing_launch/launch/velodyne_node_container.launch.py | 2 ++ 4 files changed, 20 insertions(+) diff --git a/sensing_launch/launch/velodyne_VLP16.launch.xml b/sensing_launch/launch/velodyne_VLP16.launch.xml index c2c058c1d3..4ed3433a52 100644 --- a/sensing_launch/launch/velodyne_VLP16.launch.xml +++ b/sensing_launch/launch/velodyne_VLP16.launch.xml @@ -11,6 +11,9 @@ + + + @@ -22,6 +25,9 @@ + + + diff --git a/sensing_launch/launch/velodyne_VLP32C.launch.xml b/sensing_launch/launch/velodyne_VLP32C.launch.xml index e169b945b4..cff4761cf5 100644 --- a/sensing_launch/launch/velodyne_VLP32C.launch.xml +++ b/sensing_launch/launch/velodyne_VLP32C.launch.xml @@ -11,6 +11,9 @@ + + + @@ -22,6 +25,9 @@ + + + diff --git a/sensing_launch/launch/velodyne_VLS128.launch.xml b/sensing_launch/launch/velodyne_VLS128.launch.xml index 4893e51b7b..c94e376574 100644 --- a/sensing_launch/launch/velodyne_VLS128.launch.xml +++ b/sensing_launch/launch/velodyne_VLS128.launch.xml @@ -11,6 +11,9 @@ + + + @@ -22,6 +25,9 @@ + + + diff --git a/sensing_launch/launch/velodyne_node_container.launch.py b/sensing_launch/launch/velodyne_node_container.launch.py index c9590a9785..4d711113f2 100644 --- a/sensing_launch/launch/velodyne_node_container.launch.py +++ b/sensing_launch/launch/velodyne_node_container.launch.py @@ -211,4 +211,6 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg('gps_time', 'False') add_launch_arg('input_frame', LaunchConfiguration('base_frame')) add_launch_arg('output_frame', LaunchConfiguration('base_frame')) + add_launch_arg('vehicle_param_file') + add_launch_arg('vehicle_mirror_param_file') return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) From 79b8119a899ecc7aa11c5d78ca3e7c61c25855e8 Mon Sep 17 00:00:00 2001 From: Taichi Higashide Date: Tue, 2 Mar 2021 18:02:19 +0900 Subject: [PATCH 093/851] add localization_error_monitor launch (#75) --- localization_launch/launch/localization.launch.xml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/localization_launch/launch/localization.launch.xml b/localization_launch/launch/localization.launch.xml index 151d482dea..116c00fe9e 100644 --- a/localization_launch/launch/localization.launch.xml +++ b/localization_launch/launch/localization.launch.xml @@ -27,6 +27,10 @@ + + + + From 0f1b96c365c84f90cb2bdca04cae0c9389b6de29 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Tue, 2 Mar 2021 19:20:39 +0900 Subject: [PATCH 094/851] temporary disable steering angle plugin to avoid RVIZ2 to crash (#76) Signed-off-by: mitsudome-r --- 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 3a75dca8db..6133c07bc4 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -62,7 +62,7 @@ Visualization Manager: - Class: rviz_common/Group Displays: - Class: rviz_plugins/SteeringAngle - Enabled: true + Enabled: false Left: 128 Length: 256 Name: SteeringAngle From 61993fbf2e366d2a5119192e51f5267167ec469b Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Fri, 5 Mar 2021 04:03:08 +0900 Subject: [PATCH 095/851] fix rviz settings (#77) * Points -> Squares * disable road_lanelets * visualize path of dynamic object * fix durability policy of route_marker * fix topic name * fix topic name of check point * fix some options about object --- autoware_launch/rviz/autoware.rviz | 34 +++++++++++++++--------------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 6133c07bc4..d8600f597c 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -338,8 +338,8 @@ Visualization Manager: Position Transformer: XYZ Selectable: true Size (Pixels): 1 - Size (m): 0.05000000074505806 - Style: Points + Size (m): 0.1 + Style: Squares Topic: Depth: 5 Durability Policy: Transient Local @@ -361,7 +361,7 @@ Visualization Manager: parking_lots: true parking_space: true right_lane_bound: true - road_lanelets: true + road_lanelets: false stop_lines: true traffic_light: true traffic_light_triangle: true @@ -400,8 +400,8 @@ Visualization Manager: Position Transformer: XYZ Selectable: true Size (Pixels): 2 - Size (m): 0.009999999776482582 - Style: Points + Size (m): 0.1 + Style: Squares Topic: Depth: 5 Durability Policy: Volatile @@ -433,8 +433,8 @@ Visualization Manager: Position Transformer: XYZ Selectable: true Size (Pixels): 5 - Size (m): 0.009999999776482582 - Style: Points + Size (m): 0.1 + Style: Squares Topic: Depth: 5 Durability Policy: Volatile @@ -608,8 +608,8 @@ Visualization Manager: Position Transformer: XYZ Selectable: true Size (Pixels): 10 - Size (m): 0.009999999776482582 - Style: Points + Size (m): 0.1 + Style: Squares Topic: Depth: 5 Durability Policy: Volatile @@ -641,8 +641,8 @@ Visualization Manager: Position Transformer: XYZ Selectable: true Size (Pixels): 10 - Size (m): 0.009999999776482582 - Style: Points + Size (m): 0.1 + Style: Squares Topic: Depth: 5 Durability Policy: Volatile @@ -739,9 +739,9 @@ Visualization Manager: Name: DynamicObjects Namespaces: label: true - path: false + path: true path confidence: true - position covariance: true + position covariance: false shape: true twist: true Topic: @@ -799,7 +799,7 @@ Visualization Manager: route_lanelets: true Topic: Depth: 5 - Durability Policy: Volatile + Durability Policy: Transient Local History Policy: Keep Last Reliability Policy: Reliable Value: /planning/mission_planning/route_marker @@ -1082,7 +1082,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obststacle_stop_planner/debug/marker + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true @@ -1139,7 +1139,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obststacle_avoidance_planner/debug/marker + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker Value: true Enabled: true Name: MotionPlanning @@ -1313,7 +1313,7 @@ Visualization Manager: Z position: 0 Z std deviation: 0.029999999329447746 - Class: rviz_plugins/MissionCheckpointTool - Pose Topic: mission_checkpoint + Pose Topic: /planning/mission_planning/checkpoint Theta std deviation: 0.2617993950843811 X std deviation: 0.5 Y std deviation: 0.5 From 99a662e3c4d0d39b21a01204469e3572ec6d7342 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Fri, 5 Mar 2021 06:08:00 +0900 Subject: [PATCH 096/851] add clock_publisher and autoware_version (#79) * add clock_publisher and autoware_version Signed-off-by: mitsudome-r * update package.xml Signed-off-by: mitsudome-r * update build_depends.repos Signed-off-by: mitsudome-r * fix CI Signed-off-by: mitsudome-r --- autoware_launch/launch/autoware.launch.xml | 3 +++ autoware_launch/launch/planning_simulator.launch.xml | 4 ++++ autoware_launch/package.xml | 1 + build_depends.repos | 10 +++++++--- system_launch/launch/system.launch.xml | 3 +++ system_launch/package.xml | 1 + 6 files changed, 19 insertions(+), 3 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index e168f65b24..7fdc09188a 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -64,4 +64,7 @@ + + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index c1b35ee1fc..8dded3a2ab 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -60,4 +60,8 @@ + + + + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index abcdf33a29..0ac73559a7 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -11,6 +11,7 @@ control_launch + clock_publisher localization_launch map_launch perception_launch diff --git a/build_depends.repos b/build_depends.repos index 0b96d6e6c3..ca3c4a5005 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -1,8 +1,8 @@ repositories: - dependencies/Pilot.Auto: + dependencies/AutowareArchitectureProposal.iv: type: git - url: https://github.com/tier4/Pilot.Auto.git - version: ros2-v0.8.0-beta + url: https://github.com/tier4/AutowareArchitectureProposal.iv.git + version: ros2 description/sensor/velodyne_simulator: type: git url: https://github.com/tier4/velodyne_simulator.git @@ -47,3 +47,7 @@ repositories: type: git url: https://github.com/GT-RAIL/rosauth.git version: ros2 + vendor/clock_publisher: + type: git + url: https://github.com/mitsudome-r/clock_publisher.git + version: master \ No newline at end of file diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index f3a1b43c3a..238a33a383 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -42,5 +42,8 @@ + + + diff --git a/system_launch/package.xml b/system_launch/package.xml index 1946cb6774..21ff9552c9 100644 --- a/system_launch/package.xml +++ b/system_launch/package.xml @@ -13,6 +13,7 @@ system_monitor autoware_state_monitor autoware_error_monitor + autoware_version emergency_handler ament_lint_auto From 1ae9750397455fa6ab2417b8d64093e3ec0324c9 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Thu, 4 Mar 2021 22:15:50 +0100 Subject: [PATCH 097/851] Use Livox vendor package (#40) * Use Livox vendor package * Use upstream repository --- build_depends.repos | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build_depends.repos b/build_depends.repos index ca3c4a5005..868a70019d 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -33,7 +33,7 @@ repositories: version: ros2 vendor/livox-driver: type: git - url: https://github.com/fred-apex-ai/livox_ros2_driver.git + url: https://github.com/Livox-SDK/livox_ros2_driver.git version: master vendor/usb_cam: type: git From 8d5d77a3a5145165dc76e61980c62dfd708b1a0f Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Fri, 5 Mar 2021 09:24:56 +0900 Subject: [PATCH 098/851] Fix typo in rviz config (#80) Signed-off-by: wep21 --- 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 d8600f597c..f927223a67 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -662,7 +662,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /localization/pose_estimator/monte_calro_initial_pose_marker + Value: /localization/pose_estimator/monte_carlo_initial_pose_marker Value: true Enabled: true Name: NDT From 424bde20dc381728f1c80f8c2865e2ddb2131035 Mon Sep 17 00:00:00 2001 From: HOSOKAWA Ikuto Date: Fri, 5 Mar 2021 12:31:57 +0900 Subject: [PATCH 099/851] fixed typo and added AW_ROS2_USE_SIM_TIME setting (#81) Co-authored-by: hosokawa --- autoware_launch/launch/logging_simulator.launch.xml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 67ba948c08..95925f559a 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -61,13 +61,15 @@ - + - + + + From 034aaed6ebd3988f607a925907d2d42cc4d05bd5 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 9 Mar 2021 10:44:27 +0900 Subject: [PATCH 100/851] Fix point size in rviz (#84) Signed-off-by: wep21 --- autoware_launch/rviz/autoware.rviz | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index f927223a67..072d565a46 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -338,7 +338,7 @@ Visualization Manager: Position Transformer: XYZ Selectable: true Size (Pixels): 1 - Size (m): 0.1 + Size (m): 0.02 Style: Squares Topic: Depth: 5 @@ -400,7 +400,7 @@ Visualization Manager: Position Transformer: XYZ Selectable: true Size (Pixels): 2 - Size (m): 0.1 + Size (m): 0.02 Style: Squares Topic: Depth: 5 @@ -433,7 +433,7 @@ Visualization Manager: Position Transformer: XYZ Selectable: true Size (Pixels): 5 - Size (m): 0.1 + Size (m): 0.02 Style: Squares Topic: Depth: 5 @@ -608,7 +608,7 @@ Visualization Manager: Position Transformer: XYZ Selectable: true Size (Pixels): 10 - Size (m): 0.1 + Size (m): 0.02 Style: Squares Topic: Depth: 5 @@ -641,7 +641,7 @@ Visualization Manager: Position Transformer: XYZ Selectable: true Size (Pixels): 10 - Size (m): 0.1 + Size (m): 0.02 Style: Squares Topic: Depth: 5 From bbc7b3f88fdc7bbab835a026f0ec509f9f1eeeb4 Mon Sep 17 00:00:00 2001 From: Taichi Higashide Date: Tue, 9 Mar 2021 23:03:07 +0900 Subject: [PATCH 101/851] fix bug (#85) --- sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py index 57f82c4a1c..0b333fa9c9 100644 --- a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py @@ -243,7 +243,7 @@ def launch_setup(context, *args, **kwargs): voxel_grid_outlier_filter_component = ComposableNode( package=pkg, plugin='pointcloud_preprocessor::VoxelGridOutlierFilterComponent', - name='voxel_grid_filter', + name='voxel_grid_outlier_filter', remappings=[ ('input', 'voxel_grid_filtered/pointcloud'), ('output', 'no_ground/pointcloud'), From d2d85f7cf94ffcce4770e71819e9b4ce6204b63b Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 11 Mar 2021 13:12:16 +0900 Subject: [PATCH 102/851] Use sensor data qos for pointcloud (#82) Signed-off-by: Autoware Co-authored-by: Autoware --- autoware_launch/rviz/autoware.rviz | 4 ++-- .../launch/aip_customized/pointcloud_preprocessor.launch.py | 3 +++ .../launch/aip_s1/pointcloud_preprocessor.launch.py | 3 +++ .../launch/aip_x1/pointcloud_preprocessor.launch.py | 3 +++ .../launch/aip_x2/pointcloud_preprocessor.launch.py | 3 +++ .../launch/aip_xx1/pointcloud_preprocessor.launch.py | 3 +++ .../launch/aip_xx2/pointcloud_preprocessor.launch.py | 3 +++ 7 files changed, 20 insertions(+), 2 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 072d565a46..683ab6ff70 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -406,7 +406,7 @@ Visualization Manager: Depth: 5 Durability Policy: Volatile History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /sensing/lidar/concatenated/pointcloud Use Fixed Frame: false Use rainbow: true @@ -439,7 +439,7 @@ Visualization Manager: Depth: 5 Durability Policy: Volatile History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /sensing/lidar/no_ground/pointcloud Use Fixed Frame: true Use rainbow: true diff --git a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py index a13afd6504..d18d4779c7 100644 --- a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py @@ -129,6 +129,9 @@ def launch_setup(context, *args, **kwargs): "input_topic": "/sensing/lidar/top/rectified/pointcloud", "output_topic": "/sensing/lidar/pointcloud", "type": "sensor_msgs/msg/PointCloud2", + "history": "keep_last", + "depth": 5, + "reliability": "best_effort", 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], ) diff --git a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py index a13afd6504..d18d4779c7 100644 --- a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py @@ -129,6 +129,9 @@ def launch_setup(context, *args, **kwargs): "input_topic": "/sensing/lidar/top/rectified/pointcloud", "output_topic": "/sensing/lidar/pointcloud", "type": "sensor_msgs/msg/PointCloud2", + "history": "keep_last", + "depth": 5, + "reliability": "best_effort", 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], ) diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py index 0b333fa9c9..040137f2b4 100644 --- a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py @@ -265,6 +265,9 @@ def launch_setup(context, *args, **kwargs): "input_topic": "/sensing/lidar/top/outlier_filtered/pointcloud", "output_topic": "/sensing/lidar/pointcloud", "type": "sensor_msgs/msg/PointCloud2", + "history": "keep_last", + "depth": 5, + "reliability": "best_effort", 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], ) diff --git a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py index e68a57ecb2..227146c5b7 100644 --- a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py @@ -131,6 +131,9 @@ def launch_setup(context, *args, **kwargs): "input_topic": "/sensing/lidar/top/rectified/pointcloud", "output_topic": "/sensing/lidar/pointcloud", "type": "sensor_msgs/msg/PointCloud2", + "history": "keep_last", + "depth": 5, + "reliability": "best_effort", 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], ) diff --git a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py index 3d84321720..2acaa896a1 100644 --- a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py @@ -129,6 +129,9 @@ def launch_setup(context, *args, **kwargs): "input_topic": "/sensing/lidar/top/rectified/pointcloud", "output_topic": "/sensing/lidar/pointcloud", "type": "sensor_msgs/msg/PointCloud2", + "history": "keep_last", + "depth": 5, + "reliability": "best_effort", 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], ) diff --git a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py index a13afd6504..d18d4779c7 100644 --- a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py @@ -129,6 +129,9 @@ def launch_setup(context, *args, **kwargs): "input_topic": "/sensing/lidar/top/rectified/pointcloud", "output_topic": "/sensing/lidar/pointcloud", "type": "sensor_msgs/msg/PointCloud2", + "history": "keep_last", + "depth": 5, + "reliability": "best_effort", 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], ) From e9770b81f9bdf462183669e0511ecc92ef9646c6 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Fri, 12 Mar 2021 08:48:55 +0900 Subject: [PATCH 103/851] Remove unused remappings (#88) Signed-off-by: wep21 --- sensing_launch/launch/velodyne_node_container.launch.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/sensing_launch/launch/velodyne_node_container.launch.py b/sensing_launch/launch/velodyne_node_container.launch.py index 4d711113f2..9f731a2dd6 100644 --- a/sensing_launch/launch/velodyne_node_container.launch.py +++ b/sensing_launch/launch/velodyne_node_container.launch.py @@ -89,7 +89,6 @@ def create_parameter_dict(*args): name='crop_box_filter_self', remappings=[('input', 'pointcloud_raw_ex'), ('output', 'self_cropped/pointcloud_ex'), - ('crop_box_polygon', 'self_cropped/crop_box_polygon'), ], parameters=[cropbox_parameters], ) @@ -109,7 +108,6 @@ def create_parameter_dict(*args): name='crop_box_filter_mirror', remappings=[('input', 'self_cropped/pointcloud_ex'), ('output', 'mirror_cropped/pointcloud_ex'), - ('crop_box_polygon', 'mirror_cropped/crop_box_polygon'), ], parameters=[cropbox_parameters], ) From 9c64140037d964752646286a2b6cda5bb7b6de91 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Fri, 12 Mar 2021 16:07:03 +0900 Subject: [PATCH 104/851] Ros2 fix topic name part1 (#83) * Fix topic name for behavior_velocity_planner Signed-off-by: Takagi, Isamu * Fix topic name of lane_change_planner Signed-off-by: Takagi, Isamu * Fix topic name of freespace_planner Signed-off-by: Takagi, Isamu * Fix topic name for freespace_planner Signed-off-by: Takagi, Isamu --- autoware_launch/rviz/autoware.rviz | 16 +++++++------- .../behavior_planning.launch.xml | 22 +++++++++---------- .../scenario_planning/parking.launch.xml | 4 ++-- 3 files changed, 21 insertions(+), 21 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 683ab6ff70..8a8d1a535d 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -909,7 +909,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/debug/crosswalk + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true @@ -931,7 +931,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/debug/intersection + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true @@ -952,7 +952,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/debug/blind_spot + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/blind_spot Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true @@ -967,7 +967,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/debug/traffic_light + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/traffic_light Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true @@ -980,7 +980,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/debug/stop_line + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/stop_line Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true @@ -997,7 +997,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/debug/detection_area + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true @@ -1185,7 +1185,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/debug/partial_pose_array + Value: /planning/scenario_planning/parking/freespace_planner/debug/partial_pose_array Value: true - Alpha: 0.999 Arrow Length: 0.5 @@ -1205,7 +1205,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/debug/pose_array + Value: /planning/scenario_planning/parking/freespace_planner/debug/pose_array Value: true Enabled: true Name: Parking 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 573a9b699b..a259eda073 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 @@ -4,17 +4,17 @@ - - - - - - - - - - - + + + + + + + + + + + diff --git a/planning_launch/launch/scenario_planning/parking.launch.xml b/planning_launch/launch/scenario_planning/parking.launch.xml index 726d8b7121..5ca9fdca55 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.xml +++ b/planning_launch/launch/scenario_planning/parking.launch.xml @@ -7,8 +7,8 @@ - - + + From 451cdbe8cd74f40b94dbae5ceaca63c2abee6e24 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Fri, 12 Mar 2021 16:19:41 +0900 Subject: [PATCH 105/851] Livox composable node (#87) --- sensing_launch/launch/aip_x1/lidar.launch.xml | 9 ++-- .../launch/aip_xx1/lidar.launch.xml | 6 +-- ...ssor.launch.py => livox_horizon.launch.py} | 49 ++++++++++++++++++- .../launch/livox_horizon.launch.xml | 38 -------------- 4 files changed, 52 insertions(+), 50 deletions(-) rename sensing_launch/launch/{livox_horizon_pointcloud_preprocessor.launch.py => livox_horizon.launch.py} (70%) delete mode 100644 sensing_launch/launch/livox_horizon.launch.xml diff --git a/sensing_launch/launch/aip_x1/lidar.launch.xml b/sensing_launch/launch/aip_x1/lidar.launch.xml index aca9f10e89..7857211c1a 100644 --- a/sensing_launch/launch/aip_x1/lidar.launch.xml +++ b/sensing_launch/launch/aip_x1/lidar.launch.xml @@ -23,10 +23,9 @@ - + - @@ -35,10 +34,9 @@ - + - @@ -47,10 +45,9 @@ - + - diff --git a/sensing_launch/launch/aip_xx1/lidar.launch.xml b/sensing_launch/launch/aip_xx1/lidar.launch.xml index 47732e1d36..6bb3e812b4 100644 --- a/sensing_launch/launch/aip_xx1/lidar.launch.xml +++ b/sensing_launch/launch/aip_xx1/lidar.launch.xml @@ -71,10 +71,9 @@ - + - @@ -83,10 +82,9 @@ - + - diff --git a/sensing_launch/launch/livox_horizon_pointcloud_preprocessor.launch.py b/sensing_launch/launch/livox_horizon.launch.py similarity index 70% rename from sensing_launch/launch/livox_horizon_pointcloud_preprocessor.launch.py rename to sensing_launch/launch/livox_horizon.launch.py index 57490645ab..462f64b83c 100644 --- a/sensing_launch/launch/livox_horizon_pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/livox_horizon.launch.py @@ -15,9 +15,11 @@ import launch import yaml +import os +from ament_index_python.packages import get_package_share_directory from launch.actions import DeclareLaunchArgument, OpaqueFunction 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 @@ -51,6 +53,32 @@ def launch_setup(context, *args, **kwargs): vehicle_info = get_vehicle_info(context) vehicle_mirror_info = get_vehicle_mirror_info(context) + bd_code_param_path = LaunchConfiguration('bd_code_param_path').perform(context) + with open(bd_code_param_path, 'r') as f: + bd_code_param = yaml.safe_load(f)['/**']['ros__parameters'] + + # livox driver + livox_driver_component = ComposableNode( + package='livox_ros2_driver', + plugin='livox_ros::LivoxDriver', + name='livox_driver', + parameters=[ + { + 'xfe_format': LaunchConfiguration('xfe_format'), + 'multi_topic': LaunchConfiguration('multi_topic'), + 'data_src': LaunchConfiguration('data_src'), + 'publish_freq': LaunchConfiguration('publish_freq'), + 'output_data_type': LaunchConfiguration('output_type'), + 'lvx_file_path': LaunchConfiguration('lvx_file_path'), + 'user_config_path': LaunchConfiguration('user_config_path'), + 'frame_id': LaunchConfiguration('sensor_frame'), + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', + default_value='False'), + }, + bd_code_param, + ] + ) + # set self crop box filter as a component cropbox_self_component = ComposableNode( package=pkg, @@ -113,7 +141,13 @@ def launch_setup(context, *args, **kwargs): }], ) - return [container] + loader = LoadComposableNodes( + composable_node_descriptions=[livox_driver_component], + target_container=container, + condition=launch.conditions.IfCondition(LaunchConfiguration('launch_driver')), + ) + + return [container, loader] def generate_launch_description(): @@ -123,7 +157,18 @@ def generate_launch_description(): def add_launch_arg(name: str, default_value=None): launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + add_launch_arg('xfe_format', '0') + add_launch_arg('multi_topic', '0') + add_launch_arg('data_src', '0') + add_launch_arg('publish_freq', '10.0') + add_launch_arg('output_type', '0') + add_launch_arg('lvx_file_path', 'livox_test.lvx') + add_launch_arg('user_config_path', os.path.join(get_package_share_directory( + "livox_ros2_driver"), "config/livox_lidar_config.json")) + add_launch_arg('bd_code_param_path') + add_launch_arg('launch_driver') add_launch_arg('base_frame', 'base_link') + add_launch_arg('sensor_frame', 'livox_frame') add_launch_arg('vehicle_param_file') add_launch_arg('vehicle_mirror_param_file') diff --git a/sensing_launch/launch/livox_horizon.launch.xml b/sensing_launch/launch/livox_horizon.launch.xml deleted file mode 100644 index 9fa0f5d9ea..0000000000 --- a/sensing_launch/launch/livox_horizon.launch.xml +++ /dev/null @@ -1,38 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - From 7098f8e91fada5274024036efd2d669695bffb38 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 15 Mar 2021 14:41:30 +0900 Subject: [PATCH 106/851] Fix default value of use_concat_filter and use_radius_search (#90) * Fix default value of use_concat_filter and use_radius_search Signed-off-by: Kenji Miyake * Fix lint Signed-off-by: Kenji Miyake --- .../aip_x1/pointcloud_preprocessor.launch.py | 94 +++++++++---------- 1 file changed, 45 insertions(+), 49 deletions(-) diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py index 040137f2b4..9f23e9c21c 100644 --- a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py @@ -13,16 +13,12 @@ # 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, OpaqueFunction -from launch.conditions import IfCondition, UnlessCondition -from launch.substitutions import LaunchConfiguration +from launch.substitutions import EnvironmentVariable, LaunchConfiguration from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes from launch_ros.descriptions import ComposableNode -from launch.substitutions import EnvironmentVariable +import yaml def get_vehicle_info(context): @@ -65,7 +61,7 @@ def launch_setup(context, *args, **kwargs): '/sensing/lidar/front_right/mirror_cropped/pointcloud', '/sensing/lidar/front_center/mirror_cropped/pointcloud'], 'output_frame': LaunchConfiguration('base_frame'), - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }] ) @@ -82,7 +78,7 @@ def launch_setup(context, *args, **kwargs): 'output_frame': LaunchConfiguration('base_frame'), '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'), + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }] ) @@ -105,7 +101,7 @@ def launch_setup(context, *args, **kwargs): 'min_z': -0.5, 'max_z': vehicle_info['max_height_offset'], 'negative': False, - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }] ) @@ -118,18 +114,18 @@ def launch_setup(context, *args, **kwargs): ('output', 'rough/no_ground/pointcloud'), ], parameters=[{ - "initial_max_slope": 10.0, - "general_max_slope": 10.0, - "local_max_slope": 10.0, - "min_height_threshold": 0.3, - "radial_devider_angle": 1.0, - "concentric_devider_distance": 0.0, - "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'), + 'initial_max_slope': 10.0, + 'general_max_slope': 10.0, + 'local_max_slope': 10.0, + 'min_height_threshold': 0.3, + 'radial_devider_angle': 1.0, + 'concentric_devider_distance': 0.0, + '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') }] ) @@ -151,7 +147,7 @@ def launch_setup(context, *args, **kwargs): 'min_z': -0.5, 'max_z': 0.5, 'negative': False, - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }] ) @@ -167,7 +163,7 @@ def launch_setup(context, *args, **kwargs): parameters=[{ 'voxel_size_x': 0.25, 'voxel_size_y': 0.25, - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }] ) @@ -190,7 +186,7 @@ def launch_setup(context, *args, **kwargs): 'voxel_size_y': 0.2, 'voxel_size_z': 0.2, 'debug': False, - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }] ) @@ -203,7 +199,7 @@ def launch_setup(context, *args, **kwargs): 'input_topics': ['/sensing/lidar/rough/no_ground/pointcloud', '/sensing/lidar/short_height/no_ground/pointcloud'], 'output_frame': LaunchConfiguration('base_frame'), - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }] ) @@ -216,12 +212,12 @@ def launch_setup(context, *args, **kwargs): ('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'), + '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') }] ) @@ -234,9 +230,9 @@ def launch_setup(context, *args, **kwargs): ('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'), + 'search_radius': 0.2, + 'min_neighbors': 5, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }] ) @@ -249,11 +245,11 @@ def launch_setup(context, *args, **kwargs): ('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'), + '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') }] ) @@ -262,13 +258,13 @@ def launch_setup(context, *args, **kwargs): plugin='topic_tools::RelayNode', name='relay', parameters=[{ - "input_topic": "/sensing/lidar/top/outlier_filtered/pointcloud", - "output_topic": "/sensing/lidar/pointcloud", - "type": "sensor_msgs/msg/PointCloud2", - "history": "keep_last", - "depth": 5, - "reliability": "best_effort", - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + 'input_topic': '/sensing/lidar/top/outlier_filtered/pointcloud', + 'output_topic': '/sensing/lidar/pointcloud', + 'type': 'sensor_msgs/msg/PointCloud2', + 'history': 'keep_last', + 'depth': 5, + 'reliability': 'best_effort', + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }], ) @@ -290,7 +286,7 @@ def launch_setup(context, *args, **kwargs): ], output='screen', parameters=[{ - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }], ) @@ -332,8 +328,8 @@ 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('use_concat_filter', 'true') + add_launch_arg('use_radius_search', 'true') add_launch_arg('vehicle_param_file') return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) From d3a29b6152f1b70363fa5aa6a82f288d6f69c12a Mon Sep 17 00:00:00 2001 From: Kazuki Miyahara Date: Thu, 18 Mar 2021 09:29:57 +0900 Subject: [PATCH 107/851] Fix typo in planning launch (#92) * Fix typo in planning launch * Fix remaining errors --- .../obstacle_avoidance_planner.param.yaml | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 111b83ce52..27158e72ba 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -12,14 +12,14 @@ 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_: 0.1 # minimum optimizing range around joint points + clearance_for_straight_line: 0.05 # minimum optimizing range around straight 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 # avoiding param - max_avoiding_objects_velocity_ms: .5 # maximum velocity for avoiding objects[m/s] + max_avoiding_objects_velocity_ms: 0.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 @@ -36,8 +36,8 @@ # 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 + coef_x_constrain_search_resolution: 1.0 # coef for fine sampling when exploring x direction + coef_y_constrain_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] @@ -87,4 +87,4 @@ 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 + distance_for_path_shape_change_detection: 2.0 # minimum delta dist thres for detecting path shape change From 83ccefe4abf0ebc60a6b163655ddb1dd9b81f5d1 Mon Sep 17 00:00:00 2001 From: Kazuki Miyahara Date: Thu, 18 Mar 2021 10:47:30 +0900 Subject: [PATCH 108/851] Fix typo in control launch (#91) * Fix typo in control module * change admissible_yaw_error -> admissible_yaw_error_rad --- control_launch/config/mpc_follower/mpc_follower.param.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/control_launch/config/mpc_follower/mpc_follower.param.yaml b/control_launch/config/mpc_follower/mpc_follower.param.yaml index 9156175f2d..8c4218c845 100644 --- a/control_launch/config/mpc_follower/mpc_follower.param.yaml +++ b/control_launch/config/mpc_follower/mpc_follower.param.yaml @@ -5,8 +5,8 @@ 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 + admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value + admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value # -- path smoothing -- enable_path_smoothing: false # flag for path smoothing @@ -42,7 +42,7 @@ # -- 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] + vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approximation) [s] steer_lim_deg: 40.0 # steering angle limit [deg] steer_rate_lim_dps: 600.0 # steering angle rate limit [deg/s] acceleration_limit: 2.0 # acceleration limit for trajectory velocity modification [m/ss] From 7ac05eb639140a33ed1dea035d0517e881e9a4b6 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 18 Mar 2021 15:24:00 +0900 Subject: [PATCH 109/851] [aip_x1]: Fix imu topic name (#94) Signed-off-by: wep21 --- sensing_launch/launch/aip_x1/imu.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing_launch/launch/aip_x1/imu.launch.xml b/sensing_launch/launch/aip_x1/imu.launch.xml index 9de6243b40..54214cc223 100644 --- a/sensing_launch/launch/aip_x1/imu.launch.xml +++ b/sensing_launch/launch/aip_x1/imu.launch.xml @@ -7,7 +7,7 @@ - + From 113e171705297945c749d5a2e22e3211c26288a5 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Mon, 22 Mar 2021 13:55:27 +0900 Subject: [PATCH 110/851] Add depend tag for image_transport_plugin (#95) Signed-off-by: Takagi, Isamu --- perception_launch/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/perception_launch/package.xml b/perception_launch/package.xml index 1dd2ab5264..4260e43493 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -25,6 +25,7 @@ image_transport + image_transport_plugins traffic_light_map_based_detector traffic_light_ssd_fine_detector traffic_light_classifier From 7fd235c049ce9812a1a0042fe26901082393f3a6 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 23 Mar 2021 09:50:38 +0900 Subject: [PATCH 111/851] Split system_monitor config (#98) Signed-off-by: Kenji Miyake --- .../config/system_monitor.param.yaml | 45 ------------------- .../system_monitor/cpu_monitor.param.yaml | 8 ++++ .../system_monitor/gpu_monitor.param.yaml | 8 ++++ .../system_monitor/hdd_monitor.param.yaml | 11 +++++ .../system_monitor/mem_monitor.param.yaml | 4 ++ .../system_monitor/net_monitor.param.yaml | 4 ++ .../system_monitor/ntp_monitor.param.yaml | 5 +++ .../system_monitor/process_monitor.param.yaml | 3 ++ system_launch/launch/system.launch.xml | 8 +++- 9 files changed, 50 insertions(+), 46 deletions(-) delete mode 100644 system_launch/config/system_monitor.param.yaml create mode 100644 system_launch/config/system_monitor/cpu_monitor.param.yaml create mode 100644 system_launch/config/system_monitor/gpu_monitor.param.yaml create mode 100644 system_launch/config/system_monitor/hdd_monitor.param.yaml create mode 100644 system_launch/config/system_monitor/mem_monitor.param.yaml create mode 100644 system_launch/config/system_monitor/net_monitor.param.yaml create mode 100644 system_launch/config/system_monitor/ntp_monitor.param.yaml create mode 100644 system_launch/config/system_monitor/process_monitor.param.yaml diff --git a/system_launch/config/system_monitor.param.yaml b/system_launch/config/system_monitor.param.yaml deleted file mode 100644 index 1dcc35d73c..0000000000 --- a/system_launch/config/system_monitor.param.yaml +++ /dev/null @@ -1,45 +0,0 @@ -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/config/system_monitor/cpu_monitor.param.yaml b/system_launch/config/system_monitor/cpu_monitor.param.yaml new file mode 100644 index 0000000000..e9f91cb170 --- /dev/null +++ b/system_launch/config/system_monitor/cpu_monitor.param.yaml @@ -0,0 +1,8 @@ +/**: + ros__parameters: + temp_warn: 90.0 + temp_error: 95.0 + usage_warn: 0.90 + usage_error: 1.00 + usage_avg: true + msr_reader_port: 7634 diff --git a/system_launch/config/system_monitor/gpu_monitor.param.yaml b/system_launch/config/system_monitor/gpu_monitor.param.yaml new file mode 100644 index 0000000000..d96b9f2464 --- /dev/null +++ b/system_launch/config/system_monitor/gpu_monitor.param.yaml @@ -0,0 +1,8 @@ +/**: + 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/config/system_monitor/hdd_monitor.param.yaml b/system_launch/config/system_monitor/hdd_monitor.param.yaml new file mode 100644 index 0000000000..bf687ae848 --- /dev/null +++ b/system_launch/config/system_monitor/hdd_monitor.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + hdd_reader_port: 7635 + num_disks: 1 + 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 diff --git a/system_launch/config/system_monitor/mem_monitor.param.yaml b/system_launch/config/system_monitor/mem_monitor.param.yaml new file mode 100644 index 0000000000..93688d608a --- /dev/null +++ b/system_launch/config/system_monitor/mem_monitor.param.yaml @@ -0,0 +1,4 @@ +/**: + ros__parameters: + usage_warn: 0.95 + usage_error: 0.99 diff --git a/system_launch/config/system_monitor/net_monitor.param.yaml b/system_launch/config/system_monitor/net_monitor.param.yaml new file mode 100644 index 0000000000..d0707ddba3 --- /dev/null +++ b/system_launch/config/system_monitor/net_monitor.param.yaml @@ -0,0 +1,4 @@ +/**: + ros__parameters: + devices: ["*"] + usage_warn: 0.95 diff --git a/system_launch/config/system_monitor/ntp_monitor.param.yaml b/system_launch/config/system_monitor/ntp_monitor.param.yaml new file mode 100644 index 0000000000..db54f70d1c --- /dev/null +++ b/system_launch/config/system_monitor/ntp_monitor.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + server: ntp.nict.jp + offset_warn: 0.1 + offset_error: 5.0 diff --git a/system_launch/config/system_monitor/process_monitor.param.yaml b/system_launch/config/system_monitor/process_monitor.param.yaml new file mode 100644 index 0000000000..3d6d82fae5 --- /dev/null +++ b/system_launch/config/system_monitor/process_monitor.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + num_of_procs: 5 diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index 238a33a383..be16755cc4 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -9,7 +9,13 @@ - + + + + + + + From 4e410c1d1f4c387a2495e95570d1e99dc839ff57 Mon Sep 17 00:00:00 2001 From: Kazuki Miyahara Date: Wed, 24 Mar 2021 16:58:56 +0900 Subject: [PATCH 112/851] Fix typo in perception launch files (#93) --- .../detection/camera_lidar_fusion_based_detection.launch.xml | 4 ++-- .../detection/lidar_based_detection.launch.xml | 2 +- perception_launch/launch/perception.launch.xml | 2 +- 3 files changed, 4 insertions(+), 4 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 e026e17f62..48ff2e060f 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 @@ -68,7 +68,7 @@ - + @@ -87,7 +87,7 @@ - + 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 be91b84912..0f45cc31ca 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 @@ - + diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index b259b77f4c..be963dd6b2 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -23,7 +23,7 @@ - + From 382e7f5fdf09994297b4c8f71970e99423cb6630 Mon Sep 17 00:00:00 2001 From: Kazuki Miyahara Date: Wed, 24 Mar 2021 17:04:30 +0900 Subject: [PATCH 113/851] Fix various typos in launch files (#97) --- autoware_launch/launch/autoware.launch.xml | 2 +- autoware_launch/launch/planning_simulator.launch.xml | 2 +- autoware_launch/package.xml | 2 +- .../config/mpc_follower/mpc_follower.param.yaml | 2 +- localization_launch/config/ndt_scan_matcher.param.yaml | 2 +- localization_launch/launch/util/util.launch.xml | 8 ++++---- .../motion_velocity_optimizer.param.yaml | 4 ++-- .../obstacle_avoidance_planner.param.yaml | 10 +++++----- .../launch/aip_x1/pointcloud_preprocessor.launch.py | 4 ++-- 9 files changed, 18 insertions(+), 18 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 7fdc09188a..61a73e9dd1 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -65,6 +65,6 @@ - + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 8dded3a2ab..2892cb9c87 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -62,6 +62,6 @@ - + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 0ac73559a7..1432b69685 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -20,7 +20,7 @@ system_launch vehicle_launch - + rviz2 diff --git a/control_launch/config/mpc_follower/mpc_follower.param.yaml b/control_launch/config/mpc_follower/mpc_follower.param.yaml index 8c4218c845..72a9fcd8db 100644 --- a/control_launch/config/mpc_follower/mpc_follower.param.yaml +++ b/control_launch/config/mpc_follower/mpc_follower.param.yaml @@ -34,7 +34,7 @@ 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_low_curvature_thresh_curvature: 0.00 # threshold of curvature to use "low curvature" 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 diff --git a/localization_launch/config/ndt_scan_matcher.param.yaml b/localization_launch/config/ndt_scan_matcher.param.yaml index 0956b33082..0448d1fc63 100644 --- a/localization_launch/config/ndt_scan_matcher.param.yaml +++ b/localization_launch/config/ndt_scan_matcher.param.yaml @@ -23,7 +23,7 @@ # The number of iterations required to calculate alignment max_iterations: 30 - # Threshold for deciding whetherto trust the estimation result + # Threshold for deciding whether to trust the estimation result converged_param_transform_probability: 3.0 # neighborhood search method in OMP diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index ebae50cf3f..34117469e7 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -3,7 +3,7 @@ - + @@ -15,9 +15,9 @@ - + - + @@ -32,7 +32,7 @@ - + diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.param.yaml index 5acef77dfb..f67d93e3ae 100644 --- a/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.param.yaml +++ b/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.param.yaml @@ -14,7 +14,7 @@ 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. + engage_exit_ratio: 0.5 # exit engage sequence to normal velocity planning 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 @@ -23,7 +23,7 @@ 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] + delta_yaw_threshold: 1.0472 # Allowed delta yaw between ego pose and trajectory pose [radian] max_trajectory_length: 200.0 # max trajectory length for resampling [m] min_trajectory_length: 30.0 # min trajectory length for resampling [m] diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 27158e72ba..2a1b0a6d06 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -60,7 +60,7 @@ # mpt param # vehicle param for mpt max_steer_deg: 40.0 # max steering angle [deg] - steer_tau: 0.1 # steering dynamics time constant (1d approzimation) [s] + steer_tau: 0.1 # steering dynamics time constant (1d approximation) [s] # trajectory param for mpt num_curvature_sampling_points: 5 # number of sampling points when calculating curvature @@ -76,11 +76,11 @@ yaw_error_weight: 0.0 # weight for yaw error steer_input_weight: 0.01 # weight for steering input steer_rate_weight: 1.0 # weight for steering rate - steer_acc_weight: 0.000001 # weight for steering acceration + steer_acc_weight: 0.000001 # weight for steering acceleration 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 + terminal_yaw_error_weight: 100.0 # weight for yaw error at terminal point + terminal_path_lat_error_weight: 1000.0 # weight for lateral error at path end point + terminal_path_yaw_error_weight: 1000.0 # weight for yaw error at path end point zero_ff_steer_angle: 0.5 # threshold that feed-forward angle becomes zero # replanning & trimming trajectory param outside algorithm diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py index 9f23e9c21c..2f9fcb7b10 100644 --- a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py @@ -118,8 +118,8 @@ def launch_setup(context, *args, **kwargs): 'general_max_slope': 10.0, 'local_max_slope': 10.0, 'min_height_threshold': 0.3, - 'radial_devider_angle': 1.0, - 'concentric_devider_distance': 0.0, + 'radial_divider_angle': 1.0, + 'concentric_divider_distance': 0.0, 'use_vehicle_footprint': True, 'min_x': vehicle_info['min_longitudinal_offset'], 'max_x': vehicle_info['max_longitudinal_offset'], From 8d3bcd5f070e3314f92b542fe2951a01957dd009 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Wed, 24 Mar 2021 17:29:05 +0900 Subject: [PATCH 114/851] Move individual params to a separate package (#100) Signed-off-by: Kenji Miyake --- individual_params/CMakeLists.txt | 17 +++++++++++++++++ .../livox_front_center_bd_code.param.yaml | 0 .../livox_front_left_bd_code.param.yaml | 0 .../livox_front_right_bd_code.param.yaml | 0 .../default/aip_x1/sensor_kit_calibration.yaml | 0 .../default/aip_x1/sensors_calibration.yaml | 0 .../livox_front_left_bd_code.param.yaml | 0 .../livox_front_right_bd_code.param.yaml | 0 .../aip_xx1/sensor_kit_calibration.yaml | 0 .../default/aip_xx1/sensors_calibration.yaml | 0 individual_params/package.xml | 18 ++++++++++++++++++ sensing_launch/CMakeLists.txt | 1 - sensing_launch/launch/aip_x1/lidar.launch.xml | 6 +++--- sensing_launch/launch/aip_xx1/lidar.launch.xml | 4 ++-- vehicle_launch/CMakeLists.txt | 1 - .../aip_customized/sensors_calibration.yaml | 0 .../default/aip_s1/sensors_calibration.yaml | 0 .../default/aip_x2/sensors_calibration.yaml | 0 .../default/aip_xx2/sensors_calibration.yaml | 0 .../launch/vehicle_description.launch.xml | 2 +- 20 files changed, 41 insertions(+), 8 deletions(-) create mode 100644 individual_params/CMakeLists.txt rename {sensing_launch/config/aip_x1/default => individual_params/config/default/aip_x1}/livox_front_center_bd_code.param.yaml (100%) rename {sensing_launch/config/aip_x1/default => individual_params/config/default/aip_x1}/livox_front_left_bd_code.param.yaml (100%) rename {sensing_launch/config/aip_x1/default => individual_params/config/default/aip_x1}/livox_front_right_bd_code.param.yaml (100%) rename {vehicle_launch => individual_params}/config/default/aip_x1/sensor_kit_calibration.yaml (100%) rename {vehicle_launch => individual_params}/config/default/aip_x1/sensors_calibration.yaml (100%) rename {sensing_launch/config/aip_xx1/default => individual_params/config/default/aip_xx1}/livox_front_left_bd_code.param.yaml (100%) rename {sensing_launch/config/aip_xx1/default => individual_params/config/default/aip_xx1}/livox_front_right_bd_code.param.yaml (100%) rename {vehicle_launch => individual_params}/config/default/aip_xx1/sensor_kit_calibration.yaml (100%) rename {vehicle_launch => individual_params}/config/default/aip_xx1/sensors_calibration.yaml (100%) create mode 100644 individual_params/package.xml 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_x2/sensors_calibration.yaml delete mode 100644 vehicle_launch/config/default/aip_xx2/sensors_calibration.yaml diff --git a/individual_params/CMakeLists.txt b/individual_params/CMakeLists.txt new file mode 100644 index 0000000000..1f24577885 --- /dev/null +++ b/individual_params/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.5) +project(individual_params) + +add_compile_options(-std=c++14) + +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/sensing_launch/config/aip_x1/default/livox_front_center_bd_code.param.yaml b/individual_params/config/default/aip_x1/livox_front_center_bd_code.param.yaml similarity index 100% rename from sensing_launch/config/aip_x1/default/livox_front_center_bd_code.param.yaml rename to individual_params/config/default/aip_x1/livox_front_center_bd_code.param.yaml diff --git a/sensing_launch/config/aip_x1/default/livox_front_left_bd_code.param.yaml b/individual_params/config/default/aip_x1/livox_front_left_bd_code.param.yaml similarity index 100% rename from sensing_launch/config/aip_x1/default/livox_front_left_bd_code.param.yaml rename to individual_params/config/default/aip_x1/livox_front_left_bd_code.param.yaml diff --git a/sensing_launch/config/aip_x1/default/livox_front_right_bd_code.param.yaml b/individual_params/config/default/aip_x1/livox_front_right_bd_code.param.yaml similarity index 100% rename from sensing_launch/config/aip_x1/default/livox_front_right_bd_code.param.yaml rename to individual_params/config/default/aip_x1/livox_front_right_bd_code.param.yaml diff --git a/vehicle_launch/config/default/aip_x1/sensor_kit_calibration.yaml b/individual_params/config/default/aip_x1/sensor_kit_calibration.yaml similarity index 100% rename from vehicle_launch/config/default/aip_x1/sensor_kit_calibration.yaml rename to individual_params/config/default/aip_x1/sensor_kit_calibration.yaml diff --git a/vehicle_launch/config/default/aip_x1/sensors_calibration.yaml b/individual_params/config/default/aip_x1/sensors_calibration.yaml similarity index 100% rename from vehicle_launch/config/default/aip_x1/sensors_calibration.yaml rename to individual_params/config/default/aip_x1/sensors_calibration.yaml diff --git a/sensing_launch/config/aip_xx1/default/livox_front_left_bd_code.param.yaml b/individual_params/config/default/aip_xx1/livox_front_left_bd_code.param.yaml similarity index 100% rename from sensing_launch/config/aip_xx1/default/livox_front_left_bd_code.param.yaml rename to individual_params/config/default/aip_xx1/livox_front_left_bd_code.param.yaml diff --git a/sensing_launch/config/aip_xx1/default/livox_front_right_bd_code.param.yaml b/individual_params/config/default/aip_xx1/livox_front_right_bd_code.param.yaml similarity index 100% rename from sensing_launch/config/aip_xx1/default/livox_front_right_bd_code.param.yaml rename to individual_params/config/default/aip_xx1/livox_front_right_bd_code.param.yaml diff --git a/vehicle_launch/config/default/aip_xx1/sensor_kit_calibration.yaml b/individual_params/config/default/aip_xx1/sensor_kit_calibration.yaml similarity index 100% rename from vehicle_launch/config/default/aip_xx1/sensor_kit_calibration.yaml rename to individual_params/config/default/aip_xx1/sensor_kit_calibration.yaml diff --git a/vehicle_launch/config/default/aip_xx1/sensors_calibration.yaml b/individual_params/config/default/aip_xx1/sensors_calibration.yaml similarity index 100% rename from vehicle_launch/config/default/aip_xx1/sensors_calibration.yaml rename to individual_params/config/default/aip_xx1/sensors_calibration.yaml diff --git a/individual_params/package.xml b/individual_params/package.xml new file mode 100644 index 0000000000..e15ae79541 --- /dev/null +++ b/individual_params/package.xml @@ -0,0 +1,18 @@ + + + individual_params + 0.1.0 + The individual_params package + + Kenji Miyake + Apache License 2.0 + + ament_cmake_auto + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/sensing_launch/CMakeLists.txt b/sensing_launch/CMakeLists.txt index afa58d1635..036e5b89af 100644 --- a/sensing_launch/CMakeLists.txt +++ b/sensing_launch/CMakeLists.txt @@ -12,5 +12,4 @@ endif() ament_auto_package(INSTALL_TO_SHARE launch data - config ) diff --git a/sensing_launch/launch/aip_x1/lidar.launch.xml b/sensing_launch/launch/aip_x1/lidar.launch.xml index 7857211c1a..466f4afc43 100644 --- a/sensing_launch/launch/aip_x1/lidar.launch.xml +++ b/sensing_launch/launch/aip_x1/lidar.launch.xml @@ -25,7 +25,7 @@ - + @@ -36,7 +36,7 @@ - + @@ -47,7 +47,7 @@ - + diff --git a/sensing_launch/launch/aip_xx1/lidar.launch.xml b/sensing_launch/launch/aip_xx1/lidar.launch.xml index 6bb3e812b4..97a1157317 100644 --- a/sensing_launch/launch/aip_xx1/lidar.launch.xml +++ b/sensing_launch/launch/aip_xx1/lidar.launch.xml @@ -73,7 +73,7 @@ - + @@ -84,7 +84,7 @@ - + diff --git a/vehicle_launch/CMakeLists.txt b/vehicle_launch/CMakeLists.txt index cf8c1e942d..a119aa504d 100644 --- a/vehicle_launch/CMakeLists.txt +++ b/vehicle_launch/CMakeLists.txt @@ -15,6 +15,5 @@ endif() ament_auto_package(INSTALL_TO_SHARE launch - config urdf ) 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_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_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_description.launch.xml b/vehicle_launch/launch/vehicle_description.launch.xml index d1ccd1f318..d714c27cb4 100644 --- a/vehicle_launch/launch/vehicle_description.launch.xml +++ b/vehicle_launch/launch/vehicle_description.launch.xml @@ -8,7 +8,7 @@ - + From c6ab5b94b145f381f601762bf10dd9eb1a510094 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Wed, 24 Mar 2021 17:30:46 +0900 Subject: [PATCH 115/851] Remove individual params (#101) Signed-off-by: Kenji Miyake From 7f03cd2831af73c543701999521d67dbad59016d Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Wed, 24 Mar 2021 17:45:14 +0900 Subject: [PATCH 116/851] Remove individual_params (#102) Signed-off-by: Kenji Miyake --- individual_params/CMakeLists.txt | 17 ---- .../livox_front_center_bd_code.param.yaml | 3 - .../livox_front_left_bd_code.param.yaml | 3 - .../livox_front_right_bd_code.param.yaml | 3 - .../aip_x1/sensor_kit_calibration.yaml | 28 ------ .../default/aip_x1/sensors_calibration.yaml | 7 -- .../livox_front_left_bd_code.param.yaml | 3 - .../livox_front_right_bd_code.param.yaml | 3 - .../aip_xx1/sensor_kit_calibration.yaml | 91 ------------------- .../default/aip_xx1/sensors_calibration.yaml | 28 ------ individual_params/package.xml | 18 ---- 11 files changed, 204 deletions(-) delete mode 100644 individual_params/CMakeLists.txt delete mode 100644 individual_params/config/default/aip_x1/livox_front_center_bd_code.param.yaml delete mode 100644 individual_params/config/default/aip_x1/livox_front_left_bd_code.param.yaml delete mode 100644 individual_params/config/default/aip_x1/livox_front_right_bd_code.param.yaml delete mode 100644 individual_params/config/default/aip_x1/sensor_kit_calibration.yaml delete mode 100644 individual_params/config/default/aip_x1/sensors_calibration.yaml delete mode 100644 individual_params/config/default/aip_xx1/livox_front_left_bd_code.param.yaml delete mode 100644 individual_params/config/default/aip_xx1/livox_front_right_bd_code.param.yaml delete mode 100644 individual_params/config/default/aip_xx1/sensor_kit_calibration.yaml delete mode 100644 individual_params/config/default/aip_xx1/sensors_calibration.yaml delete mode 100644 individual_params/package.xml diff --git a/individual_params/CMakeLists.txt b/individual_params/CMakeLists.txt deleted file mode 100644 index 1f24577885..0000000000 --- a/individual_params/CMakeLists.txt +++ /dev/null @@ -1,17 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(individual_params) - -add_compile_options(-std=c++14) - -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/individual_params/config/default/aip_x1/livox_front_center_bd_code.param.yaml b/individual_params/config/default/aip_x1/livox_front_center_bd_code.param.yaml deleted file mode 100644 index 083f0cc218..0000000000 --- a/individual_params/config/default/aip_x1/livox_front_center_bd_code.param.yaml +++ /dev/null @@ -1,3 +0,0 @@ -/**: - ros__parameters: - cmdline_input_bd_code: '100000000000000' diff --git a/individual_params/config/default/aip_x1/livox_front_left_bd_code.param.yaml b/individual_params/config/default/aip_x1/livox_front_left_bd_code.param.yaml deleted file mode 100644 index 083f0cc218..0000000000 --- a/individual_params/config/default/aip_x1/livox_front_left_bd_code.param.yaml +++ /dev/null @@ -1,3 +0,0 @@ -/**: - ros__parameters: - cmdline_input_bd_code: '100000000000000' diff --git a/individual_params/config/default/aip_x1/livox_front_right_bd_code.param.yaml b/individual_params/config/default/aip_x1/livox_front_right_bd_code.param.yaml deleted file mode 100644 index 083f0cc218..0000000000 --- a/individual_params/config/default/aip_x1/livox_front_right_bd_code.param.yaml +++ /dev/null @@ -1,3 +0,0 @@ -/**: - ros__parameters: - cmdline_input_bd_code: '100000000000000' diff --git a/individual_params/config/default/aip_x1/sensor_kit_calibration.yaml b/individual_params/config/default/aip_x1/sensor_kit_calibration.yaml deleted file mode 100644 index 0f3489dd61..0000000000 --- a/individual_params/config/default/aip_x1/sensor_kit_calibration.yaml +++ /dev/null @@ -1,28 +0,0 @@ -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/individual_params/config/default/aip_x1/sensors_calibration.yaml b/individual_params/config/default/aip_x1/sensors_calibration.yaml deleted file mode 100644 index 462d27f042..0000000000 --- a/individual_params/config/default/aip_x1/sensors_calibration.yaml +++ /dev/null @@ -1,7 +0,0 @@ -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/individual_params/config/default/aip_xx1/livox_front_left_bd_code.param.yaml b/individual_params/config/default/aip_xx1/livox_front_left_bd_code.param.yaml deleted file mode 100644 index 083f0cc218..0000000000 --- a/individual_params/config/default/aip_xx1/livox_front_left_bd_code.param.yaml +++ /dev/null @@ -1,3 +0,0 @@ -/**: - ros__parameters: - cmdline_input_bd_code: '100000000000000' diff --git a/individual_params/config/default/aip_xx1/livox_front_right_bd_code.param.yaml b/individual_params/config/default/aip_xx1/livox_front_right_bd_code.param.yaml deleted file mode 100644 index 083f0cc218..0000000000 --- a/individual_params/config/default/aip_xx1/livox_front_right_bd_code.param.yaml +++ /dev/null @@ -1,3 +0,0 @@ -/**: - ros__parameters: - cmdline_input_bd_code: '100000000000000' diff --git a/individual_params/config/default/aip_xx1/sensor_kit_calibration.yaml b/individual_params/config/default/aip_xx1/sensor_kit_calibration.yaml deleted file mode 100644 index d9d1f599e4..0000000000 --- a/individual_params/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/individual_params/config/default/aip_xx1/sensors_calibration.yaml b/individual_params/config/default/aip_xx1/sensors_calibration.yaml deleted file mode 100644 index 1aa0972391..0000000000 --- a/individual_params/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/individual_params/package.xml b/individual_params/package.xml deleted file mode 100644 index e15ae79541..0000000000 --- a/individual_params/package.xml +++ /dev/null @@ -1,18 +0,0 @@ - - - individual_params - 0.1.0 - The individual_params package - - Kenji Miyake - Apache License 2.0 - - ament_cmake_auto - - ament_lint_auto - ament_lint_common - - - ament_cmake - - From 5f8ad634b556124c864ddb2e5112d95ead5176cc Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Fri, 26 Mar 2021 09:46:23 +0900 Subject: [PATCH 117/851] add use_sim-time option (#99) --- autoware_launch/launch/autoware.launch.xml | 4 +++- autoware_launch/launch/planning_simulator.launch.xml | 4 +++- control_launch/launch/control.launch.xml | 1 + localization_launch/launch/localization.launch.xml | 1 + localization_launch/launch/util/util.launch.xml | 3 +++ map_launch/launch/map.launch.xml | 1 + .../launch/traffic_light_recognition/traffic_light.launch.xml | 1 + .../behavior_planning/behavior_planning.launch.xml | 2 ++ .../lane_driving/motion_planning/motion_planning.launch.xml | 1 + sensing_launch/launch/aip_customized/camera.launch.xml | 1 + sensing_launch/launch/aip_customized/gnss.launch.xml | 1 + sensing_launch/launch/aip_customized/imu.launch.xml | 2 ++ sensing_launch/launch/aip_s1/camera.launch.xml | 1 + sensing_launch/launch/aip_s1/gnss.launch.xml | 1 + sensing_launch/launch/aip_s1/imu.launch.xml | 2 ++ sensing_launch/launch/aip_x1/camera.launch.xml | 1 + sensing_launch/launch/aip_x1/gnss.launch.xml | 1 + sensing_launch/launch/aip_x1/imu.launch.xml | 1 + sensing_launch/launch/aip_x2/camera.launch.xml | 1 + sensing_launch/launch/aip_x2/gnss.launch.xml | 1 + sensing_launch/launch/aip_x2/imu.launch.xml | 2 ++ sensing_launch/launch/aip_xx1/camera.launch.xml | 2 ++ sensing_launch/launch/aip_xx1/gnss.launch.xml | 1 + sensing_launch/launch/aip_xx1/imu.launch.xml | 2 ++ sensing_launch/launch/aip_xx2/camera.launch.xml | 1 + sensing_launch/launch/aip_xx2/gnss.launch.xml | 1 + sensing_launch/launch/aip_xx2/imu.launch.xml | 2 ++ system_launch/launch/system.launch.xml | 4 +++- vehicle_launch/launch/vehicle_description.launch.xml | 1 + 29 files changed, 44 insertions(+), 3 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 61a73e9dd1..f1cc3c4d43 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -59,7 +59,9 @@ - + + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 2892cb9c87..6dd5b9789c 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -56,7 +56,9 @@ - + + + diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index f08338284d..73f1787d1c 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -43,6 +43,7 @@ + diff --git a/localization_launch/launch/localization.launch.xml b/localization_launch/launch/localization.launch.xml index 116c00fe9e..2ecbbf8c55 100644 --- a/localization_launch/launch/localization.launch.xml +++ b/localization_launch/launch/localization.launch.xml @@ -33,6 +33,7 @@ + diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 34117469e7..2f383f8266 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -16,6 +16,7 @@ + @@ -32,6 +33,7 @@ + @@ -40,6 +42,7 @@ + diff --git a/map_launch/launch/map.launch.xml b/map_launch/launch/map.launch.xml index 2d792eb3fe..67cbd208f2 100644 --- a/map_launch/launch/map.launch.xml +++ b/map_launch/launch/map.launch.xml @@ -10,6 +10,7 @@ + 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 29ad7c1a43..792ff5d5be 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -8,6 +8,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 a259eda073..503520d508 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 @@ -4,6 +4,7 @@ + @@ -47,6 +48,7 @@ autoware_planning_msgs/msg/LaneChangeCommand 'command: true' -r 10"/> + 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 6a289d9f29..b5b26caa87 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 @@ -27,6 +27,7 @@ + diff --git a/sensing_launch/launch/aip_customized/camera.launch.xml b/sensing_launch/launch/aip_customized/camera.launch.xml index 617d5fbb68..63cb15efc1 100644 --- a/sensing_launch/launch/aip_customized/camera.launch.xml +++ b/sensing_launch/launch/aip_customized/camera.launch.xml @@ -7,6 +7,7 @@ + diff --git a/sensing_launch/launch/aip_customized/gnss.launch.xml b/sensing_launch/launch/aip_customized/gnss.launch.xml index cbc257bc52..b7b4fbcc3a 100644 --- a/sensing_launch/launch/aip_customized/gnss.launch.xml +++ b/sensing_launch/launch/aip_customized/gnss.launch.xml @@ -7,6 +7,7 @@ + diff --git a/sensing_launch/launch/aip_customized/imu.launch.xml b/sensing_launch/launch/aip_customized/imu.launch.xml index 52355261b1..ab0872e596 100644 --- a/sensing_launch/launch/aip_customized/imu.launch.xml +++ b/sensing_launch/launch/aip_customized/imu.launch.xml @@ -8,6 +8,7 @@ + @@ -17,6 +18,7 @@ + diff --git a/sensing_launch/launch/aip_s1/camera.launch.xml b/sensing_launch/launch/aip_s1/camera.launch.xml index 617d5fbb68..63cb15efc1 100644 --- a/sensing_launch/launch/aip_s1/camera.launch.xml +++ b/sensing_launch/launch/aip_s1/camera.launch.xml @@ -7,6 +7,7 @@ + diff --git a/sensing_launch/launch/aip_s1/gnss.launch.xml b/sensing_launch/launch/aip_s1/gnss.launch.xml index cbc257bc52..b7b4fbcc3a 100644 --- a/sensing_launch/launch/aip_s1/gnss.launch.xml +++ b/sensing_launch/launch/aip_s1/gnss.launch.xml @@ -7,6 +7,7 @@ + diff --git a/sensing_launch/launch/aip_s1/imu.launch.xml b/sensing_launch/launch/aip_s1/imu.launch.xml index 52355261b1..ab0872e596 100644 --- a/sensing_launch/launch/aip_s1/imu.launch.xml +++ b/sensing_launch/launch/aip_s1/imu.launch.xml @@ -8,6 +8,7 @@ + @@ -17,6 +18,7 @@ + diff --git a/sensing_launch/launch/aip_x1/camera.launch.xml b/sensing_launch/launch/aip_x1/camera.launch.xml index fde088ea77..ad67a104b1 100644 --- a/sensing_launch/launch/aip_x1/camera.launch.xml +++ b/sensing_launch/launch/aip_x1/camera.launch.xml @@ -7,6 +7,7 @@ + diff --git a/sensing_launch/launch/aip_x1/gnss.launch.xml b/sensing_launch/launch/aip_x1/gnss.launch.xml index 13a62f6260..a3025ebb94 100644 --- a/sensing_launch/launch/aip_x1/gnss.launch.xml +++ b/sensing_launch/launch/aip_x1/gnss.launch.xml @@ -8,6 +8,7 @@ + diff --git a/sensing_launch/launch/aip_x1/imu.launch.xml b/sensing_launch/launch/aip_x1/imu.launch.xml index 54214cc223..d16e586dee 100644 --- a/sensing_launch/launch/aip_x1/imu.launch.xml +++ b/sensing_launch/launch/aip_x1/imu.launch.xml @@ -7,6 +7,7 @@ + diff --git a/sensing_launch/launch/aip_x2/camera.launch.xml b/sensing_launch/launch/aip_x2/camera.launch.xml index 617d5fbb68..63cb15efc1 100644 --- a/sensing_launch/launch/aip_x2/camera.launch.xml +++ b/sensing_launch/launch/aip_x2/camera.launch.xml @@ -7,6 +7,7 @@ + diff --git a/sensing_launch/launch/aip_x2/gnss.launch.xml b/sensing_launch/launch/aip_x2/gnss.launch.xml index cbc257bc52..b7b4fbcc3a 100644 --- a/sensing_launch/launch/aip_x2/gnss.launch.xml +++ b/sensing_launch/launch/aip_x2/gnss.launch.xml @@ -7,6 +7,7 @@ + diff --git a/sensing_launch/launch/aip_x2/imu.launch.xml b/sensing_launch/launch/aip_x2/imu.launch.xml index 52355261b1..ab0872e596 100644 --- a/sensing_launch/launch/aip_x2/imu.launch.xml +++ b/sensing_launch/launch/aip_x2/imu.launch.xml @@ -8,6 +8,7 @@ + @@ -17,6 +18,7 @@ + diff --git a/sensing_launch/launch/aip_xx1/camera.launch.xml b/sensing_launch/launch/aip_xx1/camera.launch.xml index 440ae57768..4ee88883db 100644 --- a/sensing_launch/launch/aip_xx1/camera.launch.xml +++ b/sensing_launch/launch/aip_xx1/camera.launch.xml @@ -10,12 +10,14 @@ + + diff --git a/sensing_launch/launch/aip_xx1/gnss.launch.xml b/sensing_launch/launch/aip_xx1/gnss.launch.xml index cbc257bc52..b7b4fbcc3a 100644 --- a/sensing_launch/launch/aip_xx1/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx1/gnss.launch.xml @@ -7,6 +7,7 @@ + diff --git a/sensing_launch/launch/aip_xx1/imu.launch.xml b/sensing_launch/launch/aip_xx1/imu.launch.xml index 52355261b1..ab0872e596 100644 --- a/sensing_launch/launch/aip_xx1/imu.launch.xml +++ b/sensing_launch/launch/aip_xx1/imu.launch.xml @@ -8,6 +8,7 @@ + @@ -17,6 +18,7 @@ + diff --git a/sensing_launch/launch/aip_xx2/camera.launch.xml b/sensing_launch/launch/aip_xx2/camera.launch.xml index 617d5fbb68..63cb15efc1 100644 --- a/sensing_launch/launch/aip_xx2/camera.launch.xml +++ b/sensing_launch/launch/aip_xx2/camera.launch.xml @@ -7,6 +7,7 @@ + diff --git a/sensing_launch/launch/aip_xx2/gnss.launch.xml b/sensing_launch/launch/aip_xx2/gnss.launch.xml index cbc257bc52..b7b4fbcc3a 100644 --- a/sensing_launch/launch/aip_xx2/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx2/gnss.launch.xml @@ -7,6 +7,7 @@ + diff --git a/sensing_launch/launch/aip_xx2/imu.launch.xml b/sensing_launch/launch/aip_xx2/imu.launch.xml index 52355261b1..ab0872e596 100644 --- a/sensing_launch/launch/aip_xx2/imu.launch.xml +++ b/sensing_launch/launch/aip_xx2/imu.launch.xml @@ -8,6 +8,7 @@ + @@ -17,6 +18,7 @@ + diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index be16755cc4..23a5a616b4 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -50,6 +50,8 @@ - + + + diff --git a/vehicle_launch/launch/vehicle_description.launch.xml b/vehicle_launch/launch/vehicle_description.launch.xml index d714c27cb4..922c07be7c 100644 --- a/vehicle_launch/launch/vehicle_description.launch.xml +++ b/vehicle_launch/launch/vehicle_description.launch.xml @@ -10,6 +10,7 @@ + From cc6469713156ef266e2c2ec3a09afdcec34d9099 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 30 Mar 2021 19:23:26 +0900 Subject: [PATCH 118/851] Format launch files (#178) Signed-off-by: Kenji Miyake --- autoware_launch/launch/autoware.launch.xml | 2 +- .../launch/logging_simulator.launch.xml | 2 +- .../launch/planning_simulator.launch.xml | 2 +- .../camera_lidar_fusion_based_detection.launch.xml | 2 +- .../motion_planning/motion_planning.launch.xml | 2 +- .../launch/aip_customized/imu.launch.xml | 2 +- sensing_launch/launch/aip_s1/imu.launch.xml | 2 +- sensing_launch/launch/aip_x1/imu.launch.xml | 2 +- sensing_launch/launch/aip_x2/imu.launch.xml | 2 +- sensing_launch/launch/aip_xx1/camera.launch.xml | 4 ++-- sensing_launch/launch/aip_xx1/imu.launch.xml | 2 +- sensing_launch/launch/aip_xx1/lidar.launch.xml | 14 +++++++------- sensing_launch/launch/aip_xx2/imu.launch.xml | 2 +- 13 files changed, 20 insertions(+), 20 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index f1cc3c4d43..a9ae8dddba 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -59,7 +59,7 @@ - + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 95925f559a..996b6ffde3 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -67,7 +67,7 @@ - + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 6dd5b9789c..73b2be1bfd 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -56,7 +56,7 @@ - + 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 48ff2e060f..8c6ced37f6 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 @@ -35,7 +35,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 b5b26caa87..3befc20922 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 @@ -26,7 +26,7 @@ - + diff --git a/sensing_launch/launch/aip_customized/imu.launch.xml b/sensing_launch/launch/aip_customized/imu.launch.xml index ab0872e596..6ae85666d3 100644 --- a/sensing_launch/launch/aip_customized/imu.launch.xml +++ b/sensing_launch/launch/aip_customized/imu.launch.xml @@ -17,7 +17,7 @@ - + diff --git a/sensing_launch/launch/aip_s1/imu.launch.xml b/sensing_launch/launch/aip_s1/imu.launch.xml index ab0872e596..6ae85666d3 100644 --- a/sensing_launch/launch/aip_s1/imu.launch.xml +++ b/sensing_launch/launch/aip_s1/imu.launch.xml @@ -17,7 +17,7 @@ - + diff --git a/sensing_launch/launch/aip_x1/imu.launch.xml b/sensing_launch/launch/aip_x1/imu.launch.xml index d16e586dee..94ce519023 100644 --- a/sensing_launch/launch/aip_x1/imu.launch.xml +++ b/sensing_launch/launch/aip_x1/imu.launch.xml @@ -6,7 +6,7 @@ - + diff --git a/sensing_launch/launch/aip_x2/imu.launch.xml b/sensing_launch/launch/aip_x2/imu.launch.xml index ab0872e596..6ae85666d3 100644 --- a/sensing_launch/launch/aip_x2/imu.launch.xml +++ b/sensing_launch/launch/aip_x2/imu.launch.xml @@ -17,7 +17,7 @@ - + diff --git a/sensing_launch/launch/aip_xx1/camera.launch.xml b/sensing_launch/launch/aip_xx1/camera.launch.xml index 4ee88883db..6b2f817078 100644 --- a/sensing_launch/launch/aip_xx1/camera.launch.xml +++ b/sensing_launch/launch/aip_xx1/camera.launch.xml @@ -9,14 +9,14 @@ - + - + diff --git a/sensing_launch/launch/aip_xx1/imu.launch.xml b/sensing_launch/launch/aip_xx1/imu.launch.xml index ab0872e596..6ae85666d3 100644 --- a/sensing_launch/launch/aip_xx1/imu.launch.xml +++ b/sensing_launch/launch/aip_xx1/imu.launch.xml @@ -17,7 +17,7 @@ - + diff --git a/sensing_launch/launch/aip_xx1/lidar.launch.xml b/sensing_launch/launch/aip_xx1/lidar.launch.xml index 97a1157317..86c567d659 100644 --- a/sensing_launch/launch/aip_xx1/lidar.launch.xml +++ b/sensing_launch/launch/aip_xx1/lidar.launch.xml @@ -16,8 +16,8 @@ - - + + @@ -32,7 +32,7 @@ - + @@ -47,7 +47,7 @@ - + @@ -62,7 +62,7 @@ - + @@ -71,7 +71,7 @@ - + @@ -82,7 +82,7 @@ - + diff --git a/sensing_launch/launch/aip_xx2/imu.launch.xml b/sensing_launch/launch/aip_xx2/imu.launch.xml index ab0872e596..6ae85666d3 100644 --- a/sensing_launch/launch/aip_xx2/imu.launch.xml +++ b/sensing_launch/launch/aip_xx2/imu.launch.xml @@ -17,7 +17,7 @@ - + From dbe43133345060a8aef838f344cdfd30d7767027 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 30 Mar 2021 20:17:20 +0900 Subject: [PATCH 119/851] Fix bug of pointcloud_preprocessor.py (#179) Signed-off-by: autoware Co-authored-by: autoware --- sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py index 2f9fcb7b10..3a96565f7f 100644 --- a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py @@ -54,7 +54,7 @@ def launch_setup(context, *args, **kwargs): package=pkg, plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', name='concatenate_data', - remappings=[('/output', 'concatenated/pointcloud')], + remappings=[('output', 'concatenated/pointcloud')], parameters=[{ 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', '/sensing/lidar/front_left/mirror_cropped/pointcloud', From 36a26f29186f85faa9ed055340d00ed542ed6142 Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Tue, 30 Mar 2021 21:32:32 +0900 Subject: [PATCH 120/851] fix ci (#180) * fix ci * add space * fix format --- integration_launch/CMakeLists.txt | 20 +++++++------- integration_launch/COLCON_IGNORE | 0 .../launch/ci_planning_simulator.launch.xml | 25 ++++++++++++++--- integration_launch/launch/release.launch.xml | 24 ++++++++++------- integration_launch/package.xml | 27 +++++++++++++++++-- 5 files changed, 72 insertions(+), 24 deletions(-) delete mode 100644 integration_launch/COLCON_IGNORE diff --git a/integration_launch/CMakeLists.txt b/integration_launch/CMakeLists.txt index d303b4a8be..c3ddc04a7d 100644 --- a/integration_launch/CMakeLists.txt +++ b/integration_launch/CMakeLists.txt @@ -1,14 +1,16 @@ -cmake_minimum_required(VERSION 2.8.3) + +cmake_minimum_required(VERSION 3.5) project(integration_launch) -find_package(catkin REQUIRED COMPONENTS - autoware_launch -) +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/integration_launch/COLCON_IGNORE b/integration_launch/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/integration_launch/launch/ci_planning_simulator.launch.xml b/integration_launch/launch/ci_planning_simulator.launch.xml index 6ee6bff390..ebbe82a5a9 100644 --- a/integration_launch/launch/ci_planning_simulator.launch.xml +++ b/integration_launch/launch/ci_planning_simulator.launch.xml @@ -1,14 +1,31 @@ - - + + + - - + + + + + + + + + + + + + + + + + + diff --git a/integration_launch/launch/release.launch.xml b/integration_launch/launch/release.launch.xml index 9c7ea3ac6e..299651f515 100644 --- a/integration_launch/launch/release.launch.xml +++ b/integration_launch/launch/release.launch.xml @@ -1,13 +1,19 @@ - - - - - - - - - + + + + + + + + + + + + + + + diff --git a/integration_launch/package.xml b/integration_launch/package.xml index 5b908622b4..2f5e95d847 100644 --- a/integration_launch/package.xml +++ b/integration_launch/package.xml @@ -6,8 +6,31 @@ Hiroyuki Obinata Apache 2 +ament_cmake_auto - catkin - autoware_launch + + control_launch + clock_publisher + localization_launch + map_launch + perception_launch + planning_launch + sensing_launch + system_launch + vehicle_launch + + rviz2 + + + autoware_web_controller + python3-tornado + python3-bson + + ament_lint_auto + ament_lint_common + + + ament_cmake + From 8cf7e3f735f22b6350d6ca3f12cb13c7ede7a1a6 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 5 Apr 2021 13:34:45 +0900 Subject: [PATCH 121/851] Replace doc by description (#182) Signed-off-by: Kenji Miyake --- autoware_launch/launch/autoware.launch.xml | 10 ++++--- .../launch/logging_simulator.launch.xml | 26 ++++++++++--------- .../launch/planning_simulator.launch.xml | 7 ++--- control_launch/launch/control.launch.xml | 2 +- .../twist_estimator.launch.xml | 4 +-- .../launch/util/util.launch.xml | 10 +++---- .../launch/aip_customized/gnss.launch.xml | 2 +- sensing_launch/launch/aip_s1/gnss.launch.xml | 2 +- sensing_launch/launch/aip_x1/gnss.launch.xml | 2 +- sensing_launch/launch/aip_x2/gnss.launch.xml | 2 +- sensing_launch/launch/aip_xx1/gnss.launch.xml | 2 +- sensing_launch/launch/aip_xx2/gnss.launch.xml | 2 +- system_launch/launch/system.launch.xml | 2 +- 13 files changed, 39 insertions(+), 34 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index a9ae8dddba..ed86d7497c 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -1,11 +1,11 @@ - + - + @@ -41,7 +41,8 @@ - + + @@ -52,7 +53,8 @@ - + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 996b6ffde3..56eff0a9cd 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -1,20 +1,20 @@ - + - - - - - - - - - + + + + + + + + + @@ -52,7 +52,8 @@ - + + @@ -63,7 +64,8 @@ - + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 73b2be1bfd..06dde9e019 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -1,11 +1,11 @@ - + - + @@ -49,7 +49,8 @@ - + + diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index 73f1787d1c..c96104736a 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -4,7 +4,7 @@ - + diff --git a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml index 8b8eb79601..4333c88614 100644 --- a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml +++ b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml @@ -1,7 +1,7 @@ - - + + diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 2f383f8266..10a272134a 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -2,13 +2,13 @@ - - - - + + + + - + diff --git a/sensing_launch/launch/aip_customized/gnss.launch.xml b/sensing_launch/launch/aip_customized/gnss.launch.xml index b7b4fbcc3a..41b447ea9b 100644 --- a/sensing_launch/launch/aip_customized/gnss.launch.xml +++ b/sensing_launch/launch/aip_customized/gnss.launch.xml @@ -21,7 +21,7 @@ - + diff --git a/sensing_launch/launch/aip_s1/gnss.launch.xml b/sensing_launch/launch/aip_s1/gnss.launch.xml index b7b4fbcc3a..41b447ea9b 100644 --- a/sensing_launch/launch/aip_s1/gnss.launch.xml +++ b/sensing_launch/launch/aip_s1/gnss.launch.xml @@ -21,7 +21,7 @@ - + diff --git a/sensing_launch/launch/aip_x1/gnss.launch.xml b/sensing_launch/launch/aip_x1/gnss.launch.xml index a3025ebb94..eda165ab6f 100644 --- a/sensing_launch/launch/aip_x1/gnss.launch.xml +++ b/sensing_launch/launch/aip_x1/gnss.launch.xml @@ -22,7 +22,7 @@ - + diff --git a/sensing_launch/launch/aip_x2/gnss.launch.xml b/sensing_launch/launch/aip_x2/gnss.launch.xml index b7b4fbcc3a..41b447ea9b 100644 --- a/sensing_launch/launch/aip_x2/gnss.launch.xml +++ b/sensing_launch/launch/aip_x2/gnss.launch.xml @@ -21,7 +21,7 @@ - + diff --git a/sensing_launch/launch/aip_xx1/gnss.launch.xml b/sensing_launch/launch/aip_xx1/gnss.launch.xml index b7b4fbcc3a..41b447ea9b 100644 --- a/sensing_launch/launch/aip_xx1/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx1/gnss.launch.xml @@ -21,7 +21,7 @@ - + diff --git a/sensing_launch/launch/aip_xx2/gnss.launch.xml b/sensing_launch/launch/aip_xx2/gnss.launch.xml index b7b4fbcc3a..41b447ea9b 100644 --- a/sensing_launch/launch/aip_xx2/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx2/gnss.launch.xml @@ -21,7 +21,7 @@ - + diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index 23a5a616b4..d0387172f2 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -1,6 +1,6 @@ - + From 5fefbb1743b2b5c5172298e7c4edef6bc140842b Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Mon, 5 Apr 2021 19:34:09 +0900 Subject: [PATCH 122/851] Sync public repo (#185) * add tier4 usbcam (#104) * add tier4 usbcam * change version * tier4/ros2 * Ros2 vehicle info param server (#96) * add vehicle info param server * delete vehicle param file Co-authored-by: taikitanaka * Ros2 fix topic name part2 (#89) * Fix topic name for traffic_light_classifier Signed-off-by: Takagi, Isamu * Fix topic name for traffic_light_visualization Signed-off-by: Takagi, Isamu * Fix topic name for traffic_light_ssd_fine_detector Signed-off-by: Takagi, Isamu Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Co-authored-by: tkimura4 Co-authored-by: taikitanaka Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> --- autoware_launch/launch/autoware.launch.xml | 2 -- .../launch/logging_simulator.launch.xml | 2 -- .../launch/planning_simulator.launch.xml | 2 -- build_depends.repos | 4 +-- control_launch/launch/control.launch.xml | 6 ---- .../traffic_light_node_container.launch.py | 28 +++++++++---------- planning_launch/launch/planning.launch.xml | 2 -- .../scenario_planning/lane_driving.launch.xml | 3 -- .../behavior_planning.launch.xml | 4 --- .../motion_planning.launch.xml | 4 --- .../scenario_planning.launch.xml | 2 -- vehicle_launch/launch/vehicle.launch.xml | 6 +++- .../launch/vehicle_interface.launch.xml | 2 -- 13 files changed, 21 insertions(+), 46 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index ed86d7497c..e3ecca790d 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -47,12 +47,10 @@ - - diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 56eff0a9cd..58be1402d7 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -58,12 +58,10 @@ - - diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 06dde9e019..88dffc43aa 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -43,12 +43,10 @@ - - diff --git a/build_depends.repos b/build_depends.repos index 868a70019d..c8f3899819 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -37,8 +37,8 @@ repositories: version: master vendor/usb_cam: type: git - url: https://github.com/flynneva/usb_cam.git - version: foxy + url: https://github.com/tier4/usb_cam.git + version: tier4/ros2 vendor/rosbridge_suite: type: git url: https://github.com/RobotWebTools/rosbridge_suite.git diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index c96104736a..0b9faa9bf8 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -1,7 +1,6 @@ - @@ -24,21 +23,18 @@ - - - @@ -51,7 +47,6 @@ - @@ -61,7 +56,6 @@ - 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 03179c7797..054b122d7f 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 @@ -84,23 +84,23 @@ def create_parameter_dict(*args): 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')] + 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'), - ('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/theora', 'debug/rois/theora')] + 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/theora', 'debug/rois/theora')] ) ], output='both', @@ -118,9 +118,9 @@ def create_parameter_dict(*args): 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')] + remappings=[('~/input/image', LaunchConfiguration('input/image')), + ('~/input/rois', 'rough/rois'), + ('~/output/rois', 'rois')] ), ], target_container=container, diff --git a/planning_launch/launch/planning.launch.xml b/planning_launch/launch/planning.launch.xml index 4c58bdfd46..bfc5e01110 100644 --- a/planning_launch/launch/planning.launch.xml +++ b/planning_launch/launch/planning.launch.xml @@ -1,5 +1,4 @@ - @@ -14,7 +13,6 @@ - diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch.xml b/planning_launch/launch/scenario_planning/lane_driving.launch.xml index 661590e042..f3d6507a5d 100644 --- a/planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving.launch.xml @@ -1,5 +1,4 @@ - @@ -8,7 +7,6 @@ - @@ -16,7 +14,6 @@ - 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 503520d508..c0870d617a 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,7 +1,6 @@ - @@ -41,7 +40,6 @@ - - - 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 3befc20922..749ce22b7a 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,5 @@ - @@ -9,7 +8,6 @@ - @@ -19,7 +17,6 @@ - @@ -40,7 +37,6 @@ - diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 94e493d5a0..469e147447 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -1,5 +1,4 @@ - @@ -27,7 +26,6 @@ - diff --git a/vehicle_launch/launch/vehicle.launch.xml b/vehicle_launch/launch/vehicle.launch.xml index 6d9c531b12..5badfec17b 100644 --- a/vehicle_launch/launch/vehicle.launch.xml +++ b/vehicle_launch/launch/vehicle.launch.xml @@ -8,6 +8,11 @@ + + + + + @@ -22,7 +27,6 @@ - diff --git a/vehicle_launch/launch/vehicle_interface.launch.xml b/vehicle_launch/launch/vehicle_interface.launch.xml index c703dec205..9867e34f0f 100644 --- a/vehicle_launch/launch/vehicle_interface.launch.xml +++ b/vehicle_launch/launch/vehicle_interface.launch.xml @@ -2,7 +2,6 @@ - @@ -14,7 +13,6 @@ - From 21fac3bd7589d8720ca97af93eba9f08a8695ff8 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 6 Apr 2021 11:00:26 +0900 Subject: [PATCH 123/851] Ros2 lsim test (#186) * Add group to launch file for var scope Signed-off-by: Takagi, Isamu * Remove pointcloud relay for localization Signed-off-by: Takagi, Isamu * Add use_sim_time Signed-off-by: Takagi, Isamu * Remove pointcloud relay for localization Signed-off-by: Takagi, Isamu Co-authored-by: Takagi, Isamu --- .../launch/logging_simulator.launch.xml | 89 ++++++++++++------- .../launch/util/util.launch.xml | 7 +- .../behavior_planning.launch.xml | 2 +- .../pointcloud_preprocessor.launch.py | 16 ---- .../aip_s1/pointcloud_preprocessor.launch.py | 16 ---- .../aip_x2/pointcloud_preprocessor.launch.py | 16 ---- .../aip_xx1/pointcloud_preprocessor.launch.py | 16 ---- .../aip_xx2/pointcloud_preprocessor.launch.py | 16 ---- 8 files changed, 61 insertions(+), 117 deletions(-) diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 58be1402d7..05bc31ebdc 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -1,10 +1,12 @@ + + @@ -20,51 +22,71 @@ - - - - - - + + + + + + + + - - - + + + + + + - - - - + + + + + + + - - - - - - + + + + + + + + + - - + + + + + - - - - + + + + + + - - + + + + - - - - + + + + + + @@ -72,5 +94,8 @@ - + + + + diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 10a272134a..f52eaacef5 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -2,7 +2,7 @@ - + @@ -16,7 +16,7 @@ - + @@ -25,12 +25,11 @@ - + - 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 c0870d617a..ef7aa103d8 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 @@ -46,7 +46,7 @@ autoware_planning_msgs/msg/LaneChangeCommand 'command: true' -r 10"/> - + diff --git a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py index d18d4779c7..381c6c1605 100644 --- a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py @@ -121,21 +121,6 @@ def launch_setup(context, *args, **kwargs): }] ) - 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", - "history": "keep_last", - "depth": 5, - "reliability": "best_effort", - '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', @@ -145,7 +130,6 @@ def launch_setup(context, *args, **kwargs): composable_node_descriptions=[ cropbox_component, ground_component, - relay_component, ], output='screen', parameters=[{ diff --git a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py index d18d4779c7..381c6c1605 100644 --- a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py @@ -121,21 +121,6 @@ def launch_setup(context, *args, **kwargs): }] ) - 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", - "history": "keep_last", - "depth": 5, - "reliability": "best_effort", - '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', @@ -145,7 +130,6 @@ def launch_setup(context, *args, **kwargs): composable_node_descriptions=[ cropbox_component, ground_component, - relay_component, ], output='screen', parameters=[{ diff --git a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py index 227146c5b7..e7d7ad6bcc 100644 --- a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py @@ -123,21 +123,6 @@ def launch_setup(context, *args, **kwargs): }] ) - 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", - "history": "keep_last", - "depth": 5, - "reliability": "best_effort", - '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', @@ -148,7 +133,6 @@ def launch_setup(context, *args, **kwargs): concat_component, cropbox_component, ground_component, - relay_component, ], output='screen', parameters=[{ diff --git a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py index 2acaa896a1..deface68cc 100644 --- a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py @@ -121,21 +121,6 @@ def launch_setup(context, *args, **kwargs): }] ) - 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", - "history": "keep_last", - "depth": 5, - "reliability": "best_effort", - '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', @@ -145,7 +130,6 @@ def launch_setup(context, *args, **kwargs): composable_node_descriptions=[ cropbox_component, ground_component, - relay_component, ], output='screen', parameters=[{ diff --git a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py index d18d4779c7..381c6c1605 100644 --- a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py @@ -121,21 +121,6 @@ def launch_setup(context, *args, **kwargs): }] ) - 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", - "history": "keep_last", - "depth": 5, - "reliability": "best_effort", - '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', @@ -145,7 +130,6 @@ def launch_setup(context, *args, **kwargs): composable_node_descriptions=[ cropbox_component, ground_component, - relay_component, ], output='screen', parameters=[{ From 443a524c01a3ad69a6a9337494cf961749a3ad1e Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 7 Apr 2021 14:51:33 +0900 Subject: [PATCH 124/851] Add multithread and intra process option (#187) * Add multithread and intra process option Signed-off-by: wep21 * Fix velodyne node container executable Signed-off-by: wep21 * Add option into aip_xx2 Signed-off-by: wep21 * Add option into aip_x2 Signed-off-by: wep21 * Add option into aip_x1 Signed-off-by: wep21 * Add option into aip_s1 Signed-off-by: wep21 * Add option into aip_customized Signed-off-by: wep21 * Add option into lidar.launch.xml Signed-off-by: wep21 --- .../launch/aip_customized/lidar.launch.xml | 2 + .../pointcloud_preprocessor.launch.py | 55 ++++++++++--- sensing_launch/launch/aip_s1/lidar.launch.xml | 2 + .../aip_s1/pointcloud_preprocessor.launch.py | 56 +++++++++---- sensing_launch/launch/aip_x1/lidar.launch.xml | 2 + .../aip_x1/pointcloud_preprocessor.launch.py | 82 +++++++++++++++---- sensing_launch/launch/aip_x2/lidar.launch.xml | 2 + .../aip_x2/pointcloud_preprocessor.launch.py | 44 ++++++++-- .../launch/aip_xx1/lidar.launch.xml | 2 + .../aip_xx1/pointcloud_preprocessor.launch.py | 51 +++++++++--- .../launch/aip_xx2/lidar.launch.xml | 2 + .../aip_xx2/pointcloud_preprocessor.launch.py | 41 ++++++++-- .../launch/velodyne_VLP16.launch.xml | 2 + .../launch/velodyne_VLP32C.launch.xml | 2 + .../launch/velodyne_VLS128.launch.xml | 2 + .../launch/velodyne_node_container.launch.py | 40 ++++++++- 16 files changed, 319 insertions(+), 68 deletions(-) diff --git a/sensing_launch/launch/aip_customized/lidar.launch.xml b/sensing_launch/launch/aip_customized/lidar.launch.xml index 742df1bd56..93d040ce3b 100644 --- a/sensing_launch/launch/aip_customized/lidar.launch.xml +++ b/sensing_launch/launch/aip_customized/lidar.launch.xml @@ -48,6 +48,8 @@ + + diff --git a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py index 381c6c1605..71eb9d844a 100644 --- a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py @@ -17,7 +17,7 @@ import yaml import launch -from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.actions import DeclareLaunchArgument, OpaqueFunction, SetLaunchConfiguration from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes @@ -59,11 +59,14 @@ def launch_setup(context, *args, **kwargs): 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', + '/sensing/lidar/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], + 'output_frame': LaunchConfiguration('base_frame'), 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) passthrough_component = ComposableNode( @@ -75,11 +78,14 @@ def launch_setup(context, *args, **kwargs): ('output', 'concatenated/pointcloud'), ], parameters=[{ - 'output_frame': 'base_link', + 'output_frame': LaunchConfiguration('base_frame'), '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'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) # set crop box filter as a component @@ -102,7 +108,10 @@ def launch_setup(context, *args, **kwargs): 'max_z': vehicle_info['max_height_offset'], 'negative': False, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) ground_component = ComposableNode( @@ -118,7 +127,10 @@ def launch_setup(context, *args, **kwargs): "local_max_slope": 10.0, "min_height_threshold": 0.2, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) # set container to run all required components in the same process @@ -126,7 +138,7 @@ def launch_setup(context, *args, **kwargs): name='pointcloud_preprocessor_container', namespace='pointcloud_preprocessor', package='rclcpp_components', - executable='component_container', + executable=LaunchConfiguration('container_executable'), composable_node_descriptions=[ cropbox_component, ground_component, @@ -141,13 +153,13 @@ def launch_setup(context, *args, **kwargs): concat_loader = LoadComposableNodes( composable_node_descriptions=[concat_component], target_container=container, - condition=launch.conditions.IfCondition(LaunchConfiguration('use_concat_filter')), + condition=IfCondition(LaunchConfiguration('use_concat_filter')), ) passthrough_loader = LoadComposableNodes( composable_node_descriptions=[passthrough_component], target_container=container, - condition=launch.conditions.UnlessCondition(LaunchConfiguration('use_concat_filter')), + condition=UnlessCondition(LaunchConfiguration('use_concat_filter')), ) return [container, concat_loader, passthrough_loader] @@ -162,5 +174,22 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg('base_frame', 'base_link') add_launch_arg('use_concat_filter', 'use_concat_filter') add_launch_arg('vehicle_param_file') + add_launch_arg('use_multithread', 'False') + add_launch_arg('use_intra_process', 'False') + + set_container_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container', + condition=UnlessCondition(LaunchConfiguration('use_multithread')) + ) + + set_container_mt_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container_mt', + condition=IfCondition(LaunchConfiguration('use_multithread')) + ) - return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) + return launch.LaunchDescription(launch_arguments + + [set_container_executable, + set_container_mt_executable] + + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_s1/lidar.launch.xml b/sensing_launch/launch/aip_s1/lidar.launch.xml index 1c1e82b419..f87e7d1538 100644 --- a/sensing_launch/launch/aip_s1/lidar.launch.xml +++ b/sensing_launch/launch/aip_s1/lidar.launch.xml @@ -48,6 +48,8 @@ + + diff --git a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py index 381c6c1605..a1724d2693 100644 --- a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py @@ -1,4 +1,3 @@ - # Copyright 2020 Tier IV, Inc. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); @@ -17,7 +16,7 @@ import yaml import launch -from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.actions import DeclareLaunchArgument, OpaqueFunction, SetLaunchConfiguration from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes @@ -59,11 +58,14 @@ def launch_setup(context, *args, **kwargs): 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', + '/sensing/lidar/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], + 'output_frame': LaunchConfiguration('base_frame'), 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) passthrough_component = ComposableNode( @@ -75,11 +77,14 @@ def launch_setup(context, *args, **kwargs): ('output', 'concatenated/pointcloud'), ], parameters=[{ - 'output_frame': 'base_link', + 'output_frame': LaunchConfiguration('base_frame'), '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'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) # set crop box filter as a component @@ -102,7 +107,10 @@ def launch_setup(context, *args, **kwargs): 'max_z': vehicle_info['max_height_offset'], 'negative': False, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) ground_component = ComposableNode( @@ -118,7 +126,10 @@ def launch_setup(context, *args, **kwargs): "local_max_slope": 10.0, "min_height_threshold": 0.2, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) # set container to run all required components in the same process @@ -126,7 +137,7 @@ def launch_setup(context, *args, **kwargs): name='pointcloud_preprocessor_container', namespace='pointcloud_preprocessor', package='rclcpp_components', - executable='component_container', + executable=LaunchConfiguration('container_executable'), composable_node_descriptions=[ cropbox_component, ground_component, @@ -141,13 +152,13 @@ def launch_setup(context, *args, **kwargs): concat_loader = LoadComposableNodes( composable_node_descriptions=[concat_component], target_container=container, - condition=launch.conditions.IfCondition(LaunchConfiguration('use_concat_filter')), + condition=IfCondition(LaunchConfiguration('use_concat_filter')), ) passthrough_loader = LoadComposableNodes( composable_node_descriptions=[passthrough_component], target_container=container, - condition=launch.conditions.UnlessCondition(LaunchConfiguration('use_concat_filter')), + condition=UnlessCondition(LaunchConfiguration('use_concat_filter')), ) return [container, concat_loader, passthrough_loader] @@ -162,5 +173,22 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg('base_frame', 'base_link') add_launch_arg('use_concat_filter', 'use_concat_filter') add_launch_arg('vehicle_param_file') + add_launch_arg('use_multithread', 'False') + add_launch_arg('use_intra_process', 'False') + + set_container_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container', + condition=UnlessCondition(LaunchConfiguration('use_multithread')) + ) + + set_container_mt_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container_mt', + condition=IfCondition(LaunchConfiguration('use_multithread')) + ) - return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) + return launch.LaunchDescription(launch_arguments + + [set_container_executable, + set_container_mt_executable] + + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_x1/lidar.launch.xml b/sensing_launch/launch/aip_x1/lidar.launch.xml index 466f4afc43..fa1212a7aa 100644 --- a/sensing_launch/launch/aip_x1/lidar.launch.xml +++ b/sensing_launch/launch/aip_x1/lidar.launch.xml @@ -60,6 +60,8 @@ + + diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py index 3a96565f7f..0d497a35c5 100644 --- a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py @@ -14,7 +14,8 @@ # limitations under the License. import launch -from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.actions import DeclareLaunchArgument, OpaqueFunction, SetLaunchConfiguration +from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import EnvironmentVariable, LaunchConfiguration from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes from launch_ros.descriptions import ComposableNode @@ -62,7 +63,10 @@ def launch_setup(context, *args, **kwargs): '/sensing/lidar/front_center/mirror_cropped/pointcloud'], 'output_frame': LaunchConfiguration('base_frame'), 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) # set PointCloud PassThrough Filter as a component @@ -79,7 +83,10 @@ def launch_setup(context, *args, **kwargs): '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') - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) # set crop box filter as a component @@ -102,7 +109,10 @@ def launch_setup(context, *args, **kwargs): 'max_z': vehicle_info['max_height_offset'], 'negative': False, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) ray_ground_filter_component = ComposableNode( @@ -126,7 +136,10 @@ def launch_setup(context, *args, **kwargs): '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') - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) short_height_obstacle_detection_area_filter_component = ComposableNode( @@ -148,7 +161,10 @@ def launch_setup(context, *args, **kwargs): 'max_z': 0.5, 'negative': False, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) vector_map_filter_component = ComposableNode( @@ -164,7 +180,10 @@ def launch_setup(context, *args, **kwargs): 'voxel_size_x': 0.25, 'voxel_size_y': 0.25, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) ransac_ground_filter_component = ComposableNode( @@ -187,7 +206,10 @@ def launch_setup(context, *args, **kwargs): 'voxel_size_z': 0.2, 'debug': False, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) concat_no_ground_component = ComposableNode( @@ -200,7 +222,10 @@ def launch_setup(context, *args, **kwargs): '/sensing/lidar/short_height/no_ground/pointcloud'], 'output_frame': LaunchConfiguration('base_frame'), 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) voxel_grid_filter_component = ComposableNode( @@ -218,7 +243,10 @@ def launch_setup(context, *args, **kwargs): 'voxel_size_y': 0.04, 'voxel_size_z': 0.08, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) radius_search_2d_outlier_filter_component = ComposableNode( @@ -233,7 +261,10 @@ def launch_setup(context, *args, **kwargs): 'search_radius': 0.2, 'min_neighbors': 5, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) voxel_grid_outlier_filter_component = ComposableNode( @@ -250,7 +281,10 @@ def launch_setup(context, *args, **kwargs): 'voxel_size_z': 100.0, 'voxel_points_threshold': 5, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) relay_component = ComposableNode( @@ -266,6 +300,9 @@ def launch_setup(context, *args, **kwargs): 'reliability': 'best_effort', 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) # set container to run all required components in the same process @@ -273,7 +310,7 @@ def launch_setup(context, *args, **kwargs): name='pointcloud_preprocessor_container', namespace='pointcloud_preprocessor', package='rclcpp_components', - executable='component_container', + executable=LaunchConfiguration('container_executable'), composable_node_descriptions=[ cropbox_component, ray_ground_filter_component, @@ -331,5 +368,22 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg('use_concat_filter', 'true') add_launch_arg('use_radius_search', 'true') add_launch_arg('vehicle_param_file') + add_launch_arg('use_multithread', 'False') + add_launch_arg('use_intra_process', 'False') + + set_container_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container', + condition=UnlessCondition(LaunchConfiguration('use_multithread')) + ) + + set_container_mt_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container_mt', + condition=IfCondition(LaunchConfiguration('use_multithread')) + ) - return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) + return launch.LaunchDescription(launch_arguments + + [set_container_executable, + set_container_mt_executable] + + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_x2/lidar.launch.xml b/sensing_launch/launch/aip_x2/lidar.launch.xml index e21dd0d479..ecaf554a04 100644 --- a/sensing_launch/launch/aip_x2/lidar.launch.xml +++ b/sensing_launch/launch/aip_x2/lidar.launch.xml @@ -48,6 +48,8 @@ + + diff --git a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py index e7d7ad6bcc..5ea6037809 100644 --- a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py @@ -17,7 +17,8 @@ import yaml import launch -from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.actions import DeclareLaunchArgument, OpaqueFunction, SetLaunchConfiguration +from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer from launch_ros.descriptions import ComposableNode @@ -64,7 +65,10 @@ def launch_setup(context, *args, **kwargs): '/sensing/lidar/right/outlier_filtered/pointcloud'], 'output_frame': 'base_link', 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) else: # set PointCloud PassThrough Filter as a component @@ -81,7 +85,10 @@ def launch_setup(context, *args, **kwargs): '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'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) # set crop box filter as a component @@ -104,7 +111,10 @@ def launch_setup(context, *args, **kwargs): 'max_z': vehicle_info['max_height_offset'], 'negative': False, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) ground_component = ComposableNode( @@ -120,7 +130,10 @@ def launch_setup(context, *args, **kwargs): "local_max_slope": 10.0, "min_height_threshold": 0.2, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) # set container to run all required components in the same process @@ -128,7 +141,7 @@ def launch_setup(context, *args, **kwargs): name='pointcloud_preprocessor_container', namespace='pointcloud_preprocessor', package='rclcpp_components', - executable='component_container', + executable=LaunchConfiguration('container_executable'), composable_node_descriptions=[ concat_component, cropbox_component, @@ -152,5 +165,22 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg('base_frame', 'base_link') add_launch_arg('use_concat_filter', 'use_concat_filter') add_launch_arg('vehicle_param_file') + add_launch_arg('use_multithread', 'False') + add_launch_arg('use_intra_process', 'False') + + set_container_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container', + condition=UnlessCondition(LaunchConfiguration('use_multithread')) + ) + + set_container_mt_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container_mt', + condition=IfCondition(LaunchConfiguration('use_multithread')) + ) - return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) + return launch.LaunchDescription(launch_arguments + + [set_container_executable, + set_container_mt_executable] + + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_xx1/lidar.launch.xml b/sensing_launch/launch/aip_xx1/lidar.launch.xml index 86c567d659..940ab9fa9c 100644 --- a/sensing_launch/launch/aip_xx1/lidar.launch.xml +++ b/sensing_launch/launch/aip_xx1/lidar.launch.xml @@ -95,6 +95,8 @@ + + diff --git a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py index deface68cc..71eb9d844a 100644 --- a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py @@ -17,7 +17,7 @@ import yaml import launch -from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.actions import DeclareLaunchArgument, OpaqueFunction, SetLaunchConfiguration from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes @@ -59,11 +59,14 @@ def launch_setup(context, *args, **kwargs): 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/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], 'output_frame': LaunchConfiguration('base_frame'), 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) passthrough_component = ComposableNode( @@ -79,7 +82,10 @@ def launch_setup(context, *args, **kwargs): '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'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) # set crop box filter as a component @@ -102,7 +108,10 @@ def launch_setup(context, *args, **kwargs): 'max_z': vehicle_info['max_height_offset'], 'negative': False, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) ground_component = ComposableNode( @@ -118,7 +127,10 @@ def launch_setup(context, *args, **kwargs): "local_max_slope": 10.0, "min_height_threshold": 0.2, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) # set container to run all required components in the same process @@ -126,7 +138,7 @@ def launch_setup(context, *args, **kwargs): name='pointcloud_preprocessor_container', namespace='pointcloud_preprocessor', package='rclcpp_components', - executable='component_container', + executable=LaunchConfiguration('container_executable'), composable_node_descriptions=[ cropbox_component, ground_component, @@ -141,13 +153,13 @@ def launch_setup(context, *args, **kwargs): concat_loader = LoadComposableNodes( composable_node_descriptions=[concat_component], target_container=container, - condition=launch.conditions.IfCondition(LaunchConfiguration('use_concat_filter')), + condition=IfCondition(LaunchConfiguration('use_concat_filter')), ) passthrough_loader = LoadComposableNodes( composable_node_descriptions=[passthrough_component], target_container=container, - condition=launch.conditions.UnlessCondition(LaunchConfiguration('use_concat_filter')), + condition=UnlessCondition(LaunchConfiguration('use_concat_filter')), ) return [container, concat_loader, passthrough_loader] @@ -162,5 +174,22 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg('base_frame', 'base_link') add_launch_arg('use_concat_filter', 'use_concat_filter') add_launch_arg('vehicle_param_file') + add_launch_arg('use_multithread', 'False') + add_launch_arg('use_intra_process', 'False') + + set_container_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container', + condition=UnlessCondition(LaunchConfiguration('use_multithread')) + ) + + set_container_mt_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container_mt', + condition=IfCondition(LaunchConfiguration('use_multithread')) + ) - return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) + return launch.LaunchDescription(launch_arguments + + [set_container_executable, + set_container_mt_executable] + + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_xx2/lidar.launch.xml b/sensing_launch/launch/aip_xx2/lidar.launch.xml index 549f085912..6b764863f1 100644 --- a/sensing_launch/launch/aip_xx2/lidar.launch.xml +++ b/sensing_launch/launch/aip_xx2/lidar.launch.xml @@ -48,6 +48,8 @@ + + diff --git a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py index 381c6c1605..ee0cd7761f 100644 --- a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py @@ -17,7 +17,7 @@ import yaml import launch -from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.actions import DeclareLaunchArgument, OpaqueFunction, SetLaunchConfiguration from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes @@ -63,7 +63,10 @@ def launch_setup(context, *args, **kwargs): '/sensing/lidar/right/outlier_filtered/pointcloud'], 'output_frame': 'base_link', 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) passthrough_component = ComposableNode( @@ -79,7 +82,10 @@ def launch_setup(context, *args, **kwargs): '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'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) # set crop box filter as a component @@ -102,7 +108,10 @@ def launch_setup(context, *args, **kwargs): 'max_z': vehicle_info['max_height_offset'], 'negative': False, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) ground_component = ComposableNode( @@ -118,7 +127,10 @@ def launch_setup(context, *args, **kwargs): "local_max_slope": 10.0, "min_height_threshold": 0.2, 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }] + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) # set container to run all required components in the same process @@ -162,5 +174,22 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg('base_frame', 'base_link') add_launch_arg('use_concat_filter', 'use_concat_filter') add_launch_arg('vehicle_param_file') + add_launch_arg('use_multithread', 'False') + add_launch_arg('use_intra_process', 'False') + + set_container_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container', + condition=UnlessCondition(LaunchConfiguration('use_multithread')) + ) + + set_container_mt_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container_mt', + condition=IfCondition(LaunchConfiguration('use_multithread')) + ) - return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) + return launch.LaunchDescription(launch_arguments + + [set_container_executable, + set_container_mt_executable] + + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/velodyne_VLP16.launch.xml b/sensing_launch/launch/velodyne_VLP16.launch.xml index 4ed3433a52..7259ed855e 100644 --- a/sensing_launch/launch/velodyne_VLP16.launch.xml +++ b/sensing_launch/launch/velodyne_VLP16.launch.xml @@ -28,6 +28,8 @@ + + diff --git a/sensing_launch/launch/velodyne_VLP32C.launch.xml b/sensing_launch/launch/velodyne_VLP32C.launch.xml index cff4761cf5..956ed204fd 100644 --- a/sensing_launch/launch/velodyne_VLP32C.launch.xml +++ b/sensing_launch/launch/velodyne_VLP32C.launch.xml @@ -28,6 +28,8 @@ + + diff --git a/sensing_launch/launch/velodyne_VLS128.launch.xml b/sensing_launch/launch/velodyne_VLS128.launch.xml index c94e376574..a5ed5f30b2 100644 --- a/sensing_launch/launch/velodyne_VLS128.launch.xml +++ b/sensing_launch/launch/velodyne_VLS128.launch.xml @@ -28,6 +28,8 @@ + + diff --git a/sensing_launch/launch/velodyne_node_container.launch.py b/sensing_launch/launch/velodyne_node_container.launch.py index 9f731a2dd6..9b68de556c 100644 --- a/sensing_launch/launch/velodyne_node_container.launch.py +++ b/sensing_launch/launch/velodyne_node_container.launch.py @@ -13,7 +13,8 @@ # limitations under the License. import launch -from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.actions import DeclareLaunchArgument, OpaqueFunction, SetLaunchConfiguration +from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import EnvironmentVariable, LaunchConfiguration from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes from launch_ros.descriptions import ComposableNode @@ -67,6 +68,9 @@ def create_parameter_dict(*args): }], remappings=[('velodyne_points', 'pointcloud_raw'), ('velodyne_points_ex', 'pointcloud_raw_ex')], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) ) @@ -91,6 +95,9 @@ def create_parameter_dict(*args): ('output', 'self_cropped/pointcloud_ex'), ], parameters=[cropbox_parameters], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) ) @@ -110,6 +117,9 @@ def create_parameter_dict(*args): ('output', 'mirror_cropped/pointcloud_ex'), ], parameters=[cropbox_parameters], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) ) @@ -125,6 +135,9 @@ def create_parameter_dict(*args): parameters=[{ 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) ) @@ -139,6 +152,9 @@ def create_parameter_dict(*args): parameters=[{ 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) ) @@ -148,7 +164,7 @@ def create_parameter_dict(*args): name='velodyne_node_container', namespace='pointcloud_preprocessor', package='rclcpp_components', - executable='component_container', + executable=LaunchConfiguration('container_executable'), composable_node_descriptions=nodes, parameters=[{ 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), @@ -211,4 +227,22 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg('output_frame', LaunchConfiguration('base_frame')) add_launch_arg('vehicle_param_file') add_launch_arg('vehicle_mirror_param_file') - return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) + add_launch_arg('use_multithread', 'False') + add_launch_arg('use_intra_process', 'False') + + set_container_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container', + condition=UnlessCondition(LaunchConfiguration('use_multithread')) + ) + + set_container_mt_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container_mt', + condition=IfCondition(LaunchConfiguration('use_multithread')) + ) + + return launch.LaunchDescription(launch_arguments + + [set_container_executable, + set_container_mt_executable] + + [OpaqueFunction(function=launch_setup)]) From 33a6efdca999971190bf05e21ef989e797724b2f Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Sat, 10 Apr 2021 17:39:42 +0900 Subject: [PATCH 125/851] Fix invalid attribute in gnss launch (#191) Signed-off-by: wep21 --- sensing_launch/launch/aip_customized/gnss.launch.xml | 3 ++- sensing_launch/launch/aip_s1/gnss.launch.xml | 3 ++- sensing_launch/launch/aip_x1/gnss.launch.xml | 3 ++- sensing_launch/launch/aip_x2/gnss.launch.xml | 3 ++- sensing_launch/launch/aip_xx1/gnss.launch.xml | 3 ++- sensing_launch/launch/aip_xx2/gnss.launch.xml | 3 ++- 6 files changed, 12 insertions(+), 6 deletions(-) diff --git a/sensing_launch/launch/aip_customized/gnss.launch.xml b/sensing_launch/launch/aip_customized/gnss.launch.xml index 41b447ea9b..a40b75b1a1 100644 --- a/sensing_launch/launch/aip_customized/gnss.launch.xml +++ b/sensing_launch/launch/aip_customized/gnss.launch.xml @@ -1,6 +1,7 @@ + @@ -21,7 +22,7 @@ - + diff --git a/sensing_launch/launch/aip_s1/gnss.launch.xml b/sensing_launch/launch/aip_s1/gnss.launch.xml index 41b447ea9b..a40b75b1a1 100644 --- a/sensing_launch/launch/aip_s1/gnss.launch.xml +++ b/sensing_launch/launch/aip_s1/gnss.launch.xml @@ -1,6 +1,7 @@ + @@ -21,7 +22,7 @@ - + diff --git a/sensing_launch/launch/aip_x1/gnss.launch.xml b/sensing_launch/launch/aip_x1/gnss.launch.xml index eda165ab6f..a67935e72b 100644 --- a/sensing_launch/launch/aip_x1/gnss.launch.xml +++ b/sensing_launch/launch/aip_x1/gnss.launch.xml @@ -2,6 +2,7 @@ + @@ -22,7 +23,7 @@ - + diff --git a/sensing_launch/launch/aip_x2/gnss.launch.xml b/sensing_launch/launch/aip_x2/gnss.launch.xml index 41b447ea9b..a40b75b1a1 100644 --- a/sensing_launch/launch/aip_x2/gnss.launch.xml +++ b/sensing_launch/launch/aip_x2/gnss.launch.xml @@ -1,6 +1,7 @@ + @@ -21,7 +22,7 @@ - + diff --git a/sensing_launch/launch/aip_xx1/gnss.launch.xml b/sensing_launch/launch/aip_xx1/gnss.launch.xml index 41b447ea9b..a40b75b1a1 100644 --- a/sensing_launch/launch/aip_xx1/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx1/gnss.launch.xml @@ -1,6 +1,7 @@ + @@ -21,7 +22,7 @@ - + diff --git a/sensing_launch/launch/aip_xx2/gnss.launch.xml b/sensing_launch/launch/aip_xx2/gnss.launch.xml index 41b447ea9b..a40b75b1a1 100644 --- a/sensing_launch/launch/aip_xx2/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx2/gnss.launch.xml @@ -1,6 +1,7 @@ + @@ -21,7 +22,7 @@ - + From 9665f91bab2eb76c0203c3497592c4176765e2cc Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Sun, 11 Apr 2021 08:58:48 +0900 Subject: [PATCH 126/851] Fix invalid attribute in twist estimator launch (#192) Signed-off-by: wep21 --- .../launch/twist_estimator/twist_estimator.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml index 4333c88614..bc9af1ca04 100644 --- a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml +++ b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml @@ -1,7 +1,7 @@ - - + + From 6f4e3e55b9521c3d6f921ebf9e06b3078796d3b9 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Mon, 12 Apr 2021 13:38:29 +0900 Subject: [PATCH 127/851] Add vehicle info param server into logging simulator (#194) Signed-off-by: wep21 --- autoware_launch/launch/logging_simulator.launch.xml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 05bc31ebdc..c7825222a7 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -29,6 +29,10 @@ + + + + From c97d9531a6281f7b3fff8d5dd32727631f731c33 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Mon, 12 Apr 2021 13:49:46 +0900 Subject: [PATCH 128/851] Fix parameter for scan phase (#193) Signed-off-by: wep21 --- sensing_launch/launch/velodyne_node_container.launch.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/sensing_launch/launch/velodyne_node_container.launch.py b/sensing_launch/launch/velodyne_node_container.launch.py index 9b68de556c..895775ed61 100644 --- a/sensing_launch/launch/velodyne_node_container.launch.py +++ b/sensing_launch/launch/velodyne_node_container.launch.py @@ -61,7 +61,8 @@ def create_parameter_dict(*args): plugin='velodyne_pointcloud::Convert', name='velodyne_convert_node', parameters=[{**create_parameter_dict('calibration', 'min_range', 'max_range', - 'num_points_thresholds', 'invalid_intensity', + 'num_points_thresholds', + 'invalid_intensity', 'frame_id', 'scan_phase'), 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), @@ -178,7 +179,7 @@ def create_parameter_dict(*args): name='velodyne_driver', parameters=[{**create_parameter_dict('device_ip', 'gps_time', 'read_once', 'read_fast', 'repeat_delay', 'frame_id', 'model', 'rpm', 'port', - 'pcap'), + 'pcap', 'scan_phase'), 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], From e5a1926356aaa585d8a800dcffbb70c09140b1b3 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Mon, 12 Apr 2021 16:42:46 +0900 Subject: [PATCH 129/851] Localization util preprocessor component (#188) Signed-off-by: wep21 --- .../launch/util/util.launch.py | 98 +++++++++++++++++++ .../launch/util/util.launch.xml | 38 ++----- 2 files changed, 105 insertions(+), 31 deletions(-) create mode 100644 localization_launch/launch/util/util.launch.py diff --git a/localization_launch/launch/util/util.launch.py b/localization_launch/launch/util/util.launch.py new file mode 100644 index 0000000000..b245b580af --- /dev/null +++ b/localization_launch/launch/util/util.launch.py @@ -0,0 +1,98 @@ +# 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, OpaqueFunction +from launch.conditions import IfCondition, UnlessCondition, LaunchConfigurationNotEquals +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch_ros.descriptions import ComposableNode +from launch.substitutions import EnvironmentVariable + + +def generate_launch_description(): + crop_box_component = ComposableNode( + package='pointcloud_preprocessor', + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter_measurement_range', + remappings=[ + ('input', LaunchConfiguration('input_sensor_points_topic')), + ('output', + 'mesurement_range/pointcloud'), + ], + parameters=[{ + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + '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, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + voxel_grid_downsample_component = ComposableNode( + package='pointcloud_preprocessor', + plugin='pointcloud_preprocessor::VoxelGridDownsampleFilterComponent', + name='voxel_grid_downsample_filter', + remappings=[ + ('input', + 'mesurement_range/pointcloud'), + ('output', + LaunchConfiguration('output_voxel_grid_downsample_sensor_points_topic')), + ], + parameters=[{ + 'voxel_size_x': 3.0, + 'voxel_size_y': 3.0, + 'voxel_size_z': 3.0, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + random_downsample_component = ComposableNode( + package='pointcloud_preprocessor', + plugin='pointcloud_preprocessor::VoxelGridDownsampleFilterComponent', + name='random_downsample_filter', + remappings=[ + ('input', + LaunchConfiguration('output_voxel_grid_downsample_sensor_points_topic')), + ('output', + LaunchConfiguration('output_downsample_sensor_points_topic')), + ], + parameters=[{ + 'sample_num': 1500, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + composable_nodes = [crop_box_component, + voxel_grid_downsample_component, + random_downsample_component] + + load_composable_nodes = LoadComposableNodes( + condition=LaunchConfigurationNotEquals('container', ''), + composable_node_descriptions=composable_nodes, + target_container=LaunchConfiguration('container'), + ) + return launch.LaunchDescription([load_composable_nodes]) diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index f52eaacef5..f9dda33dec 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -10,41 +10,17 @@ + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + From 934ba4552b7247527a04f5baf624287ae94e2830 Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Mon, 12 Apr 2021 17:40:06 +0900 Subject: [PATCH 130/851] add group (#195) --- vehicle_launch/launch/vehicle.launch.xml | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/vehicle_launch/launch/vehicle.launch.xml b/vehicle_launch/launch/vehicle.launch.xml index 5badfec17b..648f301998 100644 --- a/vehicle_launch/launch/vehicle.launch.xml +++ b/vehicle_launch/launch/vehicle.launch.xml @@ -9,9 +9,11 @@ - - - + + + + + From c77a2784d1022735e86e0e2651ff7a7891342bf6 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Wed, 14 Apr 2021 12:31:32 +0900 Subject: [PATCH 131/851] Fix incorrect remap (#183) * Fix incorrect remap Signed-off-by: Kenji Miyake * Use set_remap Signed-off-by: Kenji Miyake --- .../launch/object_recognition/prediction/prediction.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml index eefa357751..848b17ab9d 100644 --- a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml +++ b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml @@ -4,13 +4,13 @@ + - From d44cab79cd35e0c3cb27002e7fee6e02fcf7d101 Mon Sep 17 00:00:00 2001 From: hiro-ya-iv <30652835+hiro-ya-iv@users.noreply.github.com> Date: Fri, 23 Apr 2021 18:40:27 +0900 Subject: [PATCH 132/851] add septentrio_gnss_driver launcher and switch(septentrio <-> ublox) (#196) * add septentrio_gnss_driver launcher and switch(septentrio <-> ublox) * rm arg(gnss_receiver) escalation and modify septentrio_gnss_driver_node option * change gnss_receiver default septentrio to ublox * remap all septentrio_gnss_driver topic names * replace septentrio gnss driver launch type 'node' to 'include' --- sensing_launch/launch/aip_xx1/gnss.launch.xml | 28 ++++++++++++++----- 1 file changed, 21 insertions(+), 7 deletions(-) diff --git a/sensing_launch/launch/aip_xx1/gnss.launch.xml b/sensing_launch/launch/aip_xx1/gnss.launch.xml index a40b75b1a1..555f66e5ce 100644 --- a/sensing_launch/launch/aip_xx1/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx1/gnss.launch.xml @@ -1,22 +1,36 @@ + + + + + + + - - - - - + + + + + + + + + + + + - - + + From c0975532adbc72c60e2fca81db0b88687d5e6469 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Mon, 26 Apr 2021 15:27:58 +0900 Subject: [PATCH 133/851] Use set_parameter for use_sim_time (#198) * Use set_parameter for use_sim_time Signed-off-by: wep21 * Add default parameter for scenario simulator Signed-off-by: wep21 --- autoware_launch/launch/autoware.launch.xml | 1 - .../launch/logging_simulator.launch.xml | 3 +-- .../launch/planning_simulator.launch.xml | 3 ++- control_launch/launch/control.launch.xml | 1 - .../launch/localization.launch.xml | 1 - localization_launch/launch/util/util.launch.py | 3 --- map_launch/launch/map.launch.xml | 1 - .../traffic_light.launch.xml | 1 - .../behavior_planning.launch.xml | 2 -- .../motion_planning/motion_planning.launch.xml | 1 - .../launch/aip_customized/camera.launch.xml | 1 - .../launch/aip_customized/gnss.launch.xml | 1 - .../launch/aip_customized/imu.launch.xml | 2 -- .../pointcloud_preprocessor.launch.py | 7 ------- sensing_launch/launch/aip_s1/camera.launch.xml | 1 - sensing_launch/launch/aip_s1/gnss.launch.xml | 1 - sensing_launch/launch/aip_s1/imu.launch.xml | 2 -- .../aip_s1/pointcloud_preprocessor.launch.py | 7 ------- sensing_launch/launch/aip_x1/camera.launch.xml | 1 - sensing_launch/launch/aip_x1/gnss.launch.xml | 1 - sensing_launch/launch/aip_x1/imu.launch.xml | 1 - .../aip_x1/pointcloud_preprocessor.launch.py | 15 --------------- sensing_launch/launch/aip_x2/camera.launch.xml | 1 - sensing_launch/launch/aip_x2/gnss.launch.xml | 1 - sensing_launch/launch/aip_x2/imu.launch.xml | 2 -- .../aip_x2/pointcloud_preprocessor.launch.py | 7 ------- sensing_launch/launch/aip_xx1/camera.launch.xml | 2 -- sensing_launch/launch/aip_xx1/gnss.launch.xml | 1 - sensing_launch/launch/aip_xx1/imu.launch.xml | 2 -- .../aip_xx1/pointcloud_preprocessor.launch.py | 7 ------- sensing_launch/launch/aip_xx2/camera.launch.xml | 1 - sensing_launch/launch/aip_xx2/gnss.launch.xml | 1 - sensing_launch/launch/aip_xx2/imu.launch.xml | 2 -- .../aip_xx2/pointcloud_preprocessor.launch.py | 7 ------- sensing_launch/launch/livox_horizon.launch.py | 7 ------- .../launch/velodyne_node_container.launch.py | 15 --------------- system_launch/launch/system.launch.xml | 1 - .../launch/vehicle_description.launch.xml | 1 - 38 files changed, 3 insertions(+), 112 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index e3ecca790d..85292dc25c 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -60,7 +60,6 @@ - diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index c7825222a7..3361125a2e 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -19,7 +19,7 @@ - + @@ -94,7 +94,6 @@ - diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 88dffc43aa..b700adc292 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -13,6 +13,8 @@ + + @@ -56,7 +58,6 @@ - diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index 0b9faa9bf8..394c46ed79 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -39,7 +39,6 @@ - diff --git a/localization_launch/launch/localization.launch.xml b/localization_launch/launch/localization.launch.xml index 2ecbbf8c55..116c00fe9e 100644 --- a/localization_launch/launch/localization.launch.xml +++ b/localization_launch/launch/localization.launch.xml @@ -33,7 +33,6 @@ - diff --git a/localization_launch/launch/util/util.launch.py b/localization_launch/launch/util/util.launch.py index b245b580af..732102e20a 100644 --- a/localization_launch/launch/util/util.launch.py +++ b/localization_launch/launch/util/util.launch.py @@ -41,7 +41,6 @@ def generate_launch_description(): 'min_z': -30.0, 'max_z': 50.0, 'negative': False, - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -61,7 +60,6 @@ def generate_launch_description(): 'voxel_size_x': 3.0, 'voxel_size_y': 3.0, 'voxel_size_z': 3.0, - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -79,7 +77,6 @@ def generate_launch_description(): ], parameters=[{ 'sample_num': 1500, - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') diff --git a/map_launch/launch/map.launch.xml b/map_launch/launch/map.launch.xml index 67cbd208f2..2d792eb3fe 100644 --- a/map_launch/launch/map.launch.xml +++ b/map_launch/launch/map.launch.xml @@ -10,7 +10,6 @@ - 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 792ff5d5be..29ad7c1a43 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -8,7 +8,6 @@ - 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 ef7aa103d8..7a4734fb9d 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 @@ -3,7 +3,6 @@ - @@ -46,7 +45,6 @@ autoware_planning_msgs/msg/LaneChangeCommand 'command: true' -r 10"/> - 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 749ce22b7a..7b26011fa4 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 @@ -24,7 +24,6 @@ - diff --git a/sensing_launch/launch/aip_customized/camera.launch.xml b/sensing_launch/launch/aip_customized/camera.launch.xml index 63cb15efc1..617d5fbb68 100644 --- a/sensing_launch/launch/aip_customized/camera.launch.xml +++ b/sensing_launch/launch/aip_customized/camera.launch.xml @@ -7,7 +7,6 @@ - diff --git a/sensing_launch/launch/aip_customized/gnss.launch.xml b/sensing_launch/launch/aip_customized/gnss.launch.xml index a40b75b1a1..7273ddee1b 100644 --- a/sensing_launch/launch/aip_customized/gnss.launch.xml +++ b/sensing_launch/launch/aip_customized/gnss.launch.xml @@ -8,7 +8,6 @@ - diff --git a/sensing_launch/launch/aip_customized/imu.launch.xml b/sensing_launch/launch/aip_customized/imu.launch.xml index 6ae85666d3..e1eabf6ae8 100644 --- a/sensing_launch/launch/aip_customized/imu.launch.xml +++ b/sensing_launch/launch/aip_customized/imu.launch.xml @@ -8,7 +8,6 @@ - @@ -18,7 +17,6 @@ - diff --git a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py index 71eb9d844a..bf1dcba906 100644 --- a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py @@ -62,7 +62,6 @@ def launch_setup(context, *args, **kwargs): '/sensing/lidar/left/outlier_filtered/pointcloud', '/sensing/lidar/right/outlier_filtered/pointcloud'], 'output_frame': LaunchConfiguration('base_frame'), - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -81,7 +80,6 @@ def launch_setup(context, *args, **kwargs): 'output_frame': LaunchConfiguration('base_frame'), '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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -107,7 +105,6 @@ def launch_setup(context, *args, **kwargs): '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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -126,7 +123,6 @@ def launch_setup(context, *args, **kwargs): "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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -144,9 +140,6 @@ def launch_setup(context, *args, **kwargs): ground_component, ], output='screen', - parameters=[{ - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }], ) # load concat or passthrough filter diff --git a/sensing_launch/launch/aip_s1/camera.launch.xml b/sensing_launch/launch/aip_s1/camera.launch.xml index 63cb15efc1..617d5fbb68 100644 --- a/sensing_launch/launch/aip_s1/camera.launch.xml +++ b/sensing_launch/launch/aip_s1/camera.launch.xml @@ -7,7 +7,6 @@ - diff --git a/sensing_launch/launch/aip_s1/gnss.launch.xml b/sensing_launch/launch/aip_s1/gnss.launch.xml index a40b75b1a1..7273ddee1b 100644 --- a/sensing_launch/launch/aip_s1/gnss.launch.xml +++ b/sensing_launch/launch/aip_s1/gnss.launch.xml @@ -8,7 +8,6 @@ - diff --git a/sensing_launch/launch/aip_s1/imu.launch.xml b/sensing_launch/launch/aip_s1/imu.launch.xml index 6ae85666d3..e1eabf6ae8 100644 --- a/sensing_launch/launch/aip_s1/imu.launch.xml +++ b/sensing_launch/launch/aip_s1/imu.launch.xml @@ -8,7 +8,6 @@ - @@ -18,7 +17,6 @@ - diff --git a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py index a1724d2693..9e1c1cd45a 100644 --- a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py @@ -61,7 +61,6 @@ def launch_setup(context, *args, **kwargs): '/sensing/lidar/left/outlier_filtered/pointcloud', '/sensing/lidar/right/outlier_filtered/pointcloud'], 'output_frame': LaunchConfiguration('base_frame'), - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -80,7 +79,6 @@ def launch_setup(context, *args, **kwargs): 'output_frame': LaunchConfiguration('base_frame'), '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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -106,7 +104,6 @@ def launch_setup(context, *args, **kwargs): '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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -125,7 +122,6 @@ def launch_setup(context, *args, **kwargs): "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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -143,9 +139,6 @@ def launch_setup(context, *args, **kwargs): ground_component, ], output='screen', - parameters=[{ - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }], ) # load concat or passthrough filter diff --git a/sensing_launch/launch/aip_x1/camera.launch.xml b/sensing_launch/launch/aip_x1/camera.launch.xml index ad67a104b1..fde088ea77 100644 --- a/sensing_launch/launch/aip_x1/camera.launch.xml +++ b/sensing_launch/launch/aip_x1/camera.launch.xml @@ -7,7 +7,6 @@ - diff --git a/sensing_launch/launch/aip_x1/gnss.launch.xml b/sensing_launch/launch/aip_x1/gnss.launch.xml index a67935e72b..113f7be35d 100644 --- a/sensing_launch/launch/aip_x1/gnss.launch.xml +++ b/sensing_launch/launch/aip_x1/gnss.launch.xml @@ -9,7 +9,6 @@ - diff --git a/sensing_launch/launch/aip_x1/imu.launch.xml b/sensing_launch/launch/aip_x1/imu.launch.xml index 94ce519023..d3db52ec0a 100644 --- a/sensing_launch/launch/aip_x1/imu.launch.xml +++ b/sensing_launch/launch/aip_x1/imu.launch.xml @@ -7,7 +7,6 @@ - diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py index 0d497a35c5..4c8232cbc5 100644 --- a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py @@ -62,7 +62,6 @@ def launch_setup(context, *args, **kwargs): '/sensing/lidar/front_right/mirror_cropped/pointcloud', '/sensing/lidar/front_center/mirror_cropped/pointcloud'], 'output_frame': LaunchConfiguration('base_frame'), - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -82,7 +81,6 @@ def launch_setup(context, *args, **kwargs): 'output_frame': LaunchConfiguration('base_frame'), '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') }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -108,7 +106,6 @@ def launch_setup(context, *args, **kwargs): 'min_z': -0.5, 'max_z': vehicle_info['max_height_offset'], 'negative': False, - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -135,7 +132,6 @@ def launch_setup(context, *args, **kwargs): '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') }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -160,7 +156,6 @@ def launch_setup(context, *args, **kwargs): 'min_z': -0.5, 'max_z': 0.5, 'negative': False, - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -179,7 +174,6 @@ def launch_setup(context, *args, **kwargs): parameters=[{ 'voxel_size_x': 0.25, 'voxel_size_y': 0.25, - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -205,7 +199,6 @@ def launch_setup(context, *args, **kwargs): 'voxel_size_y': 0.2, 'voxel_size_z': 0.2, 'debug': False, - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -221,7 +214,6 @@ def launch_setup(context, *args, **kwargs): 'input_topics': ['/sensing/lidar/rough/no_ground/pointcloud', '/sensing/lidar/short_height/no_ground/pointcloud'], 'output_frame': LaunchConfiguration('base_frame'), - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -242,7 +234,6 @@ def launch_setup(context, *args, **kwargs): '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') }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -260,7 +251,6 @@ def launch_setup(context, *args, **kwargs): parameters=[{ 'search_radius': 0.2, 'min_neighbors': 5, - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -280,7 +270,6 @@ def launch_setup(context, *args, **kwargs): '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') }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -298,7 +287,6 @@ def launch_setup(context, *args, **kwargs): 'history': 'keep_last', 'depth': 5, 'reliability': 'best_effort', - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -322,9 +310,6 @@ def launch_setup(context, *args, **kwargs): relay_component, ], output='screen', - parameters=[{ - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False') - }], ) # load concat or passthrough filter diff --git a/sensing_launch/launch/aip_x2/camera.launch.xml b/sensing_launch/launch/aip_x2/camera.launch.xml index 63cb15efc1..617d5fbb68 100644 --- a/sensing_launch/launch/aip_x2/camera.launch.xml +++ b/sensing_launch/launch/aip_x2/camera.launch.xml @@ -7,7 +7,6 @@ - diff --git a/sensing_launch/launch/aip_x2/gnss.launch.xml b/sensing_launch/launch/aip_x2/gnss.launch.xml index a40b75b1a1..7273ddee1b 100644 --- a/sensing_launch/launch/aip_x2/gnss.launch.xml +++ b/sensing_launch/launch/aip_x2/gnss.launch.xml @@ -8,7 +8,6 @@ - diff --git a/sensing_launch/launch/aip_x2/imu.launch.xml b/sensing_launch/launch/aip_x2/imu.launch.xml index 6ae85666d3..e1eabf6ae8 100644 --- a/sensing_launch/launch/aip_x2/imu.launch.xml +++ b/sensing_launch/launch/aip_x2/imu.launch.xml @@ -8,7 +8,6 @@ - @@ -18,7 +17,6 @@ - diff --git a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py index 5ea6037809..8e0e597abd 100644 --- a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py @@ -64,7 +64,6 @@ def launch_setup(context, *args, **kwargs): '/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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -84,7 +83,6 @@ def launch_setup(context, *args, **kwargs): '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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -110,7 +108,6 @@ def launch_setup(context, *args, **kwargs): '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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -129,7 +126,6 @@ def launch_setup(context, *args, **kwargs): "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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -148,9 +144,6 @@ def launch_setup(context, *args, **kwargs): ground_component, ], output='screen', - parameters=[{ - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }], ) return [container] diff --git a/sensing_launch/launch/aip_xx1/camera.launch.xml b/sensing_launch/launch/aip_xx1/camera.launch.xml index 6b2f817078..14d7a080bc 100644 --- a/sensing_launch/launch/aip_xx1/camera.launch.xml +++ b/sensing_launch/launch/aip_xx1/camera.launch.xml @@ -10,14 +10,12 @@ - - diff --git a/sensing_launch/launch/aip_xx1/gnss.launch.xml b/sensing_launch/launch/aip_xx1/gnss.launch.xml index 555f66e5ce..2c0be5a34b 100644 --- a/sensing_launch/launch/aip_xx1/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx1/gnss.launch.xml @@ -16,7 +16,6 @@ - diff --git a/sensing_launch/launch/aip_xx1/imu.launch.xml b/sensing_launch/launch/aip_xx1/imu.launch.xml index 6ae85666d3..e1eabf6ae8 100644 --- a/sensing_launch/launch/aip_xx1/imu.launch.xml +++ b/sensing_launch/launch/aip_xx1/imu.launch.xml @@ -8,7 +8,6 @@ - @@ -18,7 +17,6 @@ - diff --git a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py index 71eb9d844a..bf1dcba906 100644 --- a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py @@ -62,7 +62,6 @@ def launch_setup(context, *args, **kwargs): '/sensing/lidar/left/outlier_filtered/pointcloud', '/sensing/lidar/right/outlier_filtered/pointcloud'], 'output_frame': LaunchConfiguration('base_frame'), - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -81,7 +80,6 @@ def launch_setup(context, *args, **kwargs): 'output_frame': LaunchConfiguration('base_frame'), '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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -107,7 +105,6 @@ def launch_setup(context, *args, **kwargs): '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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -126,7 +123,6 @@ def launch_setup(context, *args, **kwargs): "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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -144,9 +140,6 @@ def launch_setup(context, *args, **kwargs): ground_component, ], output='screen', - parameters=[{ - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }], ) # load concat or passthrough filter diff --git a/sensing_launch/launch/aip_xx2/camera.launch.xml b/sensing_launch/launch/aip_xx2/camera.launch.xml index 63cb15efc1..617d5fbb68 100644 --- a/sensing_launch/launch/aip_xx2/camera.launch.xml +++ b/sensing_launch/launch/aip_xx2/camera.launch.xml @@ -7,7 +7,6 @@ - diff --git a/sensing_launch/launch/aip_xx2/gnss.launch.xml b/sensing_launch/launch/aip_xx2/gnss.launch.xml index a40b75b1a1..7273ddee1b 100644 --- a/sensing_launch/launch/aip_xx2/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx2/gnss.launch.xml @@ -8,7 +8,6 @@ - diff --git a/sensing_launch/launch/aip_xx2/imu.launch.xml b/sensing_launch/launch/aip_xx2/imu.launch.xml index 6ae85666d3..e1eabf6ae8 100644 --- a/sensing_launch/launch/aip_xx2/imu.launch.xml +++ b/sensing_launch/launch/aip_xx2/imu.launch.xml @@ -8,7 +8,6 @@ - @@ -18,7 +17,6 @@ - diff --git a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py index ee0cd7761f..95af0e098b 100644 --- a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py @@ -62,7 +62,6 @@ def launch_setup(context, *args, **kwargs): '/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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -81,7 +80,6 @@ def launch_setup(context, *args, **kwargs): '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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -107,7 +105,6 @@ def launch_setup(context, *args, **kwargs): '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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -126,7 +123,6 @@ def launch_setup(context, *args, **kwargs): "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'), }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -144,9 +140,6 @@ def launch_setup(context, *args, **kwargs): ground_component, ], output='screen', - parameters=[{ - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }], ) # load concat or passthrough filter diff --git a/sensing_launch/launch/livox_horizon.launch.py b/sensing_launch/launch/livox_horizon.launch.py index 462f64b83c..93907c22d4 100644 --- a/sensing_launch/launch/livox_horizon.launch.py +++ b/sensing_launch/launch/livox_horizon.launch.py @@ -72,8 +72,6 @@ def launch_setup(context, *args, **kwargs): 'lvx_file_path': LaunchConfiguration('lvx_file_path'), 'user_config_path': LaunchConfiguration('user_config_path'), 'frame_id': LaunchConfiguration('sensor_frame'), - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', - default_value='False'), }, bd_code_param, ] @@ -98,7 +96,6 @@ def launch_setup(context, *args, **kwargs): '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'), }] ) @@ -121,7 +118,6 @@ def launch_setup(context, *args, **kwargs): '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'), }] ) @@ -136,9 +132,6 @@ def launch_setup(context, *args, **kwargs): cropbox_mirror_component, ], output='screen', - parameters=[{ - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }], ) loader = LoadComposableNodes( diff --git a/sensing_launch/launch/velodyne_node_container.launch.py b/sensing_launch/launch/velodyne_node_container.launch.py index 895775ed61..972a5716a4 100644 --- a/sensing_launch/launch/velodyne_node_container.launch.py +++ b/sensing_launch/launch/velodyne_node_container.launch.py @@ -64,8 +64,6 @@ def create_parameter_dict(*args): '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')], @@ -77,8 +75,6 @@ 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') vehicle_info = get_vehicle_info(context) cropbox_parameters['min_x'] = vehicle_info['min_longitudinal_offset'] @@ -133,9 +129,6 @@ def create_parameter_dict(*args): ('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'), - }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') }], @@ -150,9 +143,6 @@ def create_parameter_dict(*args): ('input', 'rectified/pointcloud_ex'), ('output', 'outlier_filtered/pointcloud') ], - parameters=[{ - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') }], @@ -167,9 +157,6 @@ def create_parameter_dict(*args): package='rclcpp_components', executable=LaunchConfiguration('container_executable'), composable_node_descriptions=nodes, - parameters=[{ - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), - }], ) driver_component = ComposableNode( @@ -180,8 +167,6 @@ def create_parameter_dict(*args): parameters=[{**create_parameter_dict('device_ip', 'gps_time', 'read_once', 'read_fast', 'repeat_delay', 'frame_id', 'model', 'rpm', 'port', 'pcap', 'scan_phase'), - 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', - default_value='False'), }], ) diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index d0387172f2..ea941660e1 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -51,7 +51,6 @@ - diff --git a/vehicle_launch/launch/vehicle_description.launch.xml b/vehicle_launch/launch/vehicle_description.launch.xml index 922c07be7c..d714c27cb4 100644 --- a/vehicle_launch/launch/vehicle_description.launch.xml +++ b/vehicle_launch/launch/vehicle_description.launch.xml @@ -10,7 +10,6 @@ - From 642a3a645e090bb08fd6188f8deaa08852383de1 Mon Sep 17 00:00:00 2001 From: Taichi Higashide Date: Tue, 27 Apr 2021 10:51:43 +0900 Subject: [PATCH 134/851] change system_monitor.launch.xml to launch.py (#203) --- system_launch/launch/system.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index ea941660e1..4a1baa6090 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -8,7 +8,7 @@ - + From 46670fb0261cb424f0fbeae7faa6b1c2b1c08e6d Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 27 Apr 2021 20:43:38 +0900 Subject: [PATCH 135/851] Add control composed launch (#201) Signed-off-by: wep21 --- autoware_launch/launch/autoware.launch.xml | 2 +- .../launch/logging_simulator.launch.xml | 2 +- .../launch/planning_simulator.launch.xml | 2 +- control_launch/launch/control.launch.py | 364 ++++++++++++++++++ 4 files changed, 367 insertions(+), 3 deletions(-) create mode 100644 control_launch/launch/control.launch.py diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 85292dc25c..e2ac2f6097 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -50,7 +50,7 @@ - + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 3361125a2e..0f95d3eab8 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -86,7 +86,7 @@ - + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index b700adc292..7df77473bd 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -48,7 +48,7 @@ - + diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py new file mode 100644 index 0000000000..f0a5702359 --- /dev/null +++ b/control_launch/launch/control.launch.py @@ -0,0 +1,364 @@ +# 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, GroupAction,\ + OpaqueFunction, SetLaunchConfiguration +from launch.conditions import IfCondition, LaunchConfigurationEquals, UnlessCondition +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes, PushRosNamespace +from launch_ros.descriptions import ComposableNode +from launch_ros.substitutions import FindPackageShare + +import yaml + + +def launch_setup(context, *args, **kwargs): + mpc_follower_param_path = \ + LaunchConfiguration('mpc_follower_param_path').perform(context) + with open(mpc_follower_param_path, 'r') as f: + mpc_follower_param = yaml.safe_load(f)['/**']['ros__parameters'] + pure_pursuit_param_path = \ + LaunchConfiguration('pure_pursuit_param_path').perform(context) + with open(pure_pursuit_param_path, 'r') as f: + pure_pursuit_param = yaml.safe_load(f)['/**']['ros__parameters'] + velocity_controller_param_path = \ + LaunchConfiguration('velocity_controller_param_path').perform(context) + with open(velocity_controller_param_path, 'r') as f: + velocity_controller_param = yaml.safe_load(f)['/**']['ros__parameters'] + vehicle_cmd_gate_param_path = \ + LaunchConfiguration('vehicle_cmd_gate_param_path').perform(context) + with open(vehicle_cmd_gate_param_path, 'r') as f: + vehicle_cmd_gate_param = yaml.safe_load(f)['/**']['ros__parameters'] + # mpc follower + mpc_follower_component = ComposableNode( + package='mpc_follower', + plugin='MPCFollower', + name='mpc_follower', + namespace='trajectory_follower', + remappings=[ + ('~/input/reference_trajectory', '/planning/scenario_planning/trajectory'), + ('~/input/current_velocity', '/localization/twist'), + ('~/input/current_steering', '/vehicle/status/steering'), + ('~/output/control_raw', 'lateral/control_cmd'), + ('~/output/predicted_trajectory', 'predicted_trajectory'), + ], + parameters=[ + mpc_follower_param, + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + # pure pursuit + pure_pursuit_component = ComposableNode( + package='pure_pursuit', + plugin='PurePursuitNode', + name='pure_pursuit', + namespace='trajectory_follower', + remappings=[ + ('input/reference_trajectory', '/planning/scenario_planning/trajectory'), + ('input/current_velocity', '/localization/twist'), + ('output/control_raw', 'lateral/control_cmd'), + ], + parameters=[ + pure_pursuit_param, + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + # velocity controller + velocity_controller_component = ComposableNode( + package='velocity_controller', + plugin='VelocityController', + name='velocity_controller', + namespace='trajectory_follower', + remappings=[ + ('~/current_velocity', '/localization/twist'), + ('~/control_cmd', 'longitudinal/control_cmd'), + ('~/current_trajectory', '/planning/scenario_planning/trajectory'), + ], + parameters=[ + velocity_controller_param, + { + 'control_rate': LaunchConfiguration('control_rate'), + 'show_debug_info': LaunchConfiguration('show_debug_info'), + 'enable_smooth_stop': LaunchConfiguration('enable_smooth_stop'), + 'enable_pub_debug': LaunchConfiguration('enable_pub_debug'), + } + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + # latlon muxer + latlon_muxer_component = ComposableNode( + package='latlon_muxer', + plugin='LatLonMuxer', + name='latlon_muxer', + namespace='trajectory_follower', + remappings=[ + ('input/lateral/control_cmd', 'lateral/control_cmd'), + ('input/longitudinal/control_cmd', 'longitudinal/control_cmd'), + ('output/control_cmd', 'control_cmd'), + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + # lane departure checker + lane_departure_component = ComposableNode( + package='lane_departure_checker', + plugin='lane_departure_checker::LaneDepartureCheckerNode', + name='lane_departure_checker_node', + namespace='trajectory_follower', + remappings=[ + ('~/input/twist', '/localization/twist'), + ('~/input/lanelet_map_bin', '/map/vector_map'), + ('~/input/route', '/planning/mission_planning/route'), + ('~/input/reference_trajectory', '/planning/scenario_planning/trajectory'), + ('~/input/predicted_trajectory', '/control/trajectory_follower/predicted_trajectory'), + ], + parameters=[ + [ + FindPackageShare('lane_departure_checker'), + '/config/lane_departure_checker.param.yaml' + ] + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + # shift decider + shift_decider_component = ComposableNode( + package='shift_decider', + plugin='ShiftDecider', + name='shift_decider', + remappings=[ + ('input/control_cmd', '/control/trajectory_follower/control_cmd'), + ('output/shift_cmd', '/control/shift_decider/shift_cmd'), + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + # vehicle cmd gate + vehicle_cmd_gate_component = ComposableNode( + package='vehicle_cmd_gate', + plugin='VehicleCmdGate', + name='vehicle_cmd_gate', + remappings=[ + ('input/engage', '/autoware/engage'), + ('input/system_emergency', '/system/emergency/is_emergency'), + ('input/external_emergency_stop', '/remote/emergency_stop'), + ('input/emergency', '/system/emergency/is_emergency'), + ('input/gate_mode', '/remote/gate_mode_cmd'), + ('input/steering', '/vehicle/status/steering'), + + ('input/auto/control_cmd', 'trajectory_follower/control_cmd'), + ('input/auto/turn_signal_cmd', '/planning/turn_signal_decider/turn_signal_cmd'), + ('input/auto/shift_cmd', '/control/shift_decider/shift_cmd'), + + ('input/remote/control_cmd', '/remote/control_cmd'), + ('input/remote/turn_signal_cmd', '/remote/turn_signal_cmd'), + ('input/remote/shift_cmd', '/remote/shift_cmd'), + + ('input/emergency/control_cmd', 'input/emergency/control_cmd'), + ('input/emergency/turn_signal_cmd', '/system/emergency/turn_signal_cmd'), + ('input/emergency/shift_cmd', '/system/emergency/shift_cmd'), + + ('output/vehicle_cmd', 'vehicle_cmd'), + ('output/control_cmd', '/control/control_cmd'), + ('output/shift_cmd', '/control/shift_cmd'), + ('output/turn_signal_cmd', '/control/turn_signal_cmd'), + ('output/gate_mode', '/control/current_gate_mode'), + + ('~/service/external_emergency_stop', '~/external_emergency_stop'), + ('~/service/clear_external_emergency_stop', '~/clear_external_emergency_stop'), + ], + parameters=[ + vehicle_cmd_gate_param, + { + 'use_emergency_handling': LaunchConfiguration('use_emergency_handling'), + 'use_external_emergency_stop': LaunchConfiguration('use_external_emergency_stop'), + } + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + # remote cmd converter + remote_cmd_converter_component = ComposableNode( + package='remote_cmd_converter', + plugin='RemoteCmdConverter', + name='remote_cmd_converter', + remappings=[ + ('in/raw_control_cmd', '/remote/raw_control_cmd'), + ('in/shift_cmd', '/remote/shift_cmd'), + ('in/emergency_stop', '/remote/emergency_stop'), + ('in/current_gate_mode', '/control/current_gate_mode'), + ('in/twist', '/localization/twist'), + ('out/control_cmd', '/remote/control_cmd'), + ('out/latest_raw_control_cmd', '/remote/latest_raw_control_cmd'), + ], + parameters=[ + { + 'csv_path_accel_map': LaunchConfiguration('csv_path_accel_map'), + 'csv_path_brake_map': LaunchConfiguration('csv_path_brake_map'), + + 'ref_vel_gain': LaunchConfiguration('ref_vel_gain'), + 'wait_for_first_topic': LaunchConfiguration('wait_for_first_topic'), + 'control_command_timeout': LaunchConfiguration('control_command_timeout'), + 'emergency_stop_timeout': LaunchConfiguration('emergency_stop_timeout'), + } + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='control_container', + namespace='', + package='rclcpp_components', + executable=LaunchConfiguration('container_executable'), + composable_node_descriptions=[ + velocity_controller_component, + latlon_muxer_component, + lane_departure_component, + shift_decider_component, + vehicle_cmd_gate_component + ], + ) + + mpc_follower_loader = LoadComposableNodes( + composable_node_descriptions=[mpc_follower_component], + target_container=container, + condition=LaunchConfigurationEquals( + 'lateral_control_mode', 'mpc_follower' + ), + ) + + pure_pursuit_loader = LoadComposableNodes( + composable_node_descriptions=[pure_pursuit_component], + target_container=container, + condition=LaunchConfigurationEquals( + 'lateral_control_mode', 'pure_pursuit' + ), + ) + + group = GroupAction([ + PushRosNamespace('control'), + container, + mpc_follower_loader, + pure_pursuit_loader + ]) + + return [group] + + +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('lateral_control_mode', 'mpc_follower') + add_launch_arg( + 'mpc_follower_param_path', + [ + FindPackageShare('control_launch'), + '/config/mpc_follower/mpc_follower.param.yaml' + ] + ) + add_launch_arg( + 'pure_pursuit_param_path', + [ + FindPackageShare('control_launch'), + '/config/pure_pursuit/pure_pursuit.param.yaml' + ] + ) + add_launch_arg( + 'velocity_controller_param_path', + [ + FindPackageShare('control_launch'), + '/config/velocity_controller/velocity_controller.param.yaml' + ] + ) + add_launch_arg( + 'vehicle_cmd_gate_param_path', + [ + FindPackageShare('control_launch'), + '/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml' + ] + ) + + # velocity controller + add_launch_arg('control_rate', '30.0') + add_launch_arg('show_debug_info', 'false') + add_launch_arg('enable_smooth_stop', 'true') + add_launch_arg('enable_pub_debug', 'true') + + # vehicle cmd gate + add_launch_arg('use_emergency_handling', 'false') + add_launch_arg('use_external_emergency_stop', 'true') + + # remote cmd converter + add_launch_arg( + 'csv_path_accel_map', + [ + FindPackageShare('raw_vehicle_cmd_converter'), + '/data/default/accel_map.csv' + ] + ) + add_launch_arg( + 'csv_path_brake_map', + [ + FindPackageShare('raw_vehicle_cmd_converter'), + '/data/default/brake_map.csv' + ] + ) + add_launch_arg('ref_vel_gain', '3.0') + add_launch_arg('wait_for_first_topic', 'true') + add_launch_arg('control_command_timeout', '1.0') + add_launch_arg('emergency_stop_timeout', '3.0') + + add_launch_arg('use_intra_process', 'false') + add_launch_arg('use_multithread', 'false') + set_container_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container', + condition=UnlessCondition(LaunchConfiguration('use_multithread')) + ) + set_container_mt_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container_mt', + condition=IfCondition(LaunchConfiguration('use_multithread')) + ) + return launch.LaunchDescription( + launch_arguments + + [set_container_executable, + set_container_mt_executable] + + [ + OpaqueFunction(function=launch_setup) + ] + ) From b097685b35d7da5a4d9f1dcc6d6bf9b37e7f5d68 Mon Sep 17 00:00:00 2001 From: Kosuke Murakami Date: Wed, 28 Apr 2021 17:13:26 +0900 Subject: [PATCH 136/851] add param for psim v2 (#197) * add param for psim v2 Signed-off-by: kosuke murakami * Update to pass var 'scenario_simulation' to dummy_perception_publisher * Update dummy_perception_publisher's arg-name Co-authored-by: yamacir-kit --- .../launch/planning_simulator.launch.xml | 9 ++++++--- vehicle_launch/launch/vehicle.launch.xml | 2 ++ vehicle_launch/launch/vehicle_interface.launch.xml | 13 ++++++++----- 3 files changed, 16 insertions(+), 8 deletions(-) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 7df77473bd..b387fc7c19 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -6,6 +6,7 @@ + @@ -13,6 +14,7 @@ + @@ -22,6 +24,7 @@ + @@ -39,6 +42,7 @@ + @@ -57,11 +61,10 @@ - - + - + diff --git a/vehicle_launch/launch/vehicle.launch.xml b/vehicle_launch/launch/vehicle.launch.xml index 648f301998..17f9cf8389 100644 --- a/vehicle_launch/launch/vehicle.launch.xml +++ b/vehicle_launch/launch/vehicle.launch.xml @@ -6,6 +6,7 @@ + @@ -28,6 +29,7 @@ + diff --git a/vehicle_launch/launch/vehicle_interface.launch.xml b/vehicle_launch/launch/vehicle_interface.launch.xml index 9867e34f0f..f7af0bfa1b 100644 --- a/vehicle_launch/launch/vehicle_interface.launch.xml +++ b/vehicle_launch/launch/vehicle_interface.launch.xml @@ -1,6 +1,7 @@ + @@ -10,11 +11,13 @@ - - - - - + + + + + + + From 9363fc7bb02d13a06bf9d3813df9db4007ad589b Mon Sep 17 00:00:00 2001 From: Keisuke Shima Date: Wed, 28 Apr 2021 23:27:13 +0900 Subject: [PATCH 137/851] Feature/porting v0.9.1 master (#202) * add simulation arg (#174) * add simulation arg * add comment * change arg name * add parameter use_empty_dynamic_object_publisher into perception.launch (#176) Signed-off-by: Azumi Suzuki Co-authored-by: Yusuke FUJII Co-authored-by: s-azumi <38061530+s-azumi@users.noreply.github.com> --- autoware_launch/launch/planning_simulator.launch.xml | 4 +++- perception_launch/launch/perception.launch.xml | 10 +++++++++- 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index b387fc7c19..b4d6b9afd4 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -17,13 +17,15 @@ + + - + diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index be963dd6b2..193e7066e3 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -22,13 +22,14 @@ + - + @@ -70,6 +71,13 @@ + + + + + + + From 954b4ade678f769f756bda3bc3c6f35b1442c37e Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Sat, 8 May 2021 00:26:17 +0900 Subject: [PATCH 138/851] Fix mistakes in control.launch.py (#209) * Fix typo in control.launch.py Signed-off-by: Kenji Miyake * Add remote_cmd_converter_component Signed-off-by: Kenji Miyake --- control_launch/launch/control.launch.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index f0a5702359..a18df00c3c 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -181,7 +181,7 @@ def launch_setup(context, *args, **kwargs): ('input/remote/turn_signal_cmd', '/remote/turn_signal_cmd'), ('input/remote/shift_cmd', '/remote/shift_cmd'), - ('input/emergency/control_cmd', 'input/emergency/control_cmd'), + ('input/emergency/control_cmd', '/system/emergency/control_cmd'), ('input/emergency/turn_signal_cmd', '/system/emergency/turn_signal_cmd'), ('input/emergency/shift_cmd', '/system/emergency/shift_cmd'), @@ -247,7 +247,8 @@ def launch_setup(context, *args, **kwargs): latlon_muxer_component, lane_departure_component, shift_decider_component, - vehicle_cmd_gate_component + vehicle_cmd_gate_component, + remote_cmd_converter_component, ], ) From 7b7b06fef7494baaa6d6a3581246cc7b36b31c54 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Sat, 8 May 2021 03:03:17 +0900 Subject: [PATCH 139/851] Feature/add external cmd selector (#206) * Add remote_cmd_selector to control.launch (#172) * Add remote_cmd_selector to control.launch Signed-off-by: Kenji Miyake * Rename remote_cmd_selector to external_cmd_selector Signed-off-by: Kenji Miyake * Change default external cmd source (#173) Signed-off-by: Kenji Miyake * modify to use control.launch.xml * add external_cmd_selector to control.launch.py * Fix remapping in control.launch.py Signed-off-by: Kenji Miyake * Fix remapping in control.launch.py again Signed-off-by: Kenji Miyake Co-authored-by: Keisuke Shima --- control_launch/launch/control.launch.py | 44 ++++++++++++++++++++---- control_launch/launch/control.launch.xml | 37 ++++++++++++++++++-- 2 files changed, 73 insertions(+), 8 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index a18df00c3c..8df28d4e8b 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -177,9 +177,9 @@ def launch_setup(context, *args, **kwargs): ('input/auto/turn_signal_cmd', '/planning/turn_signal_decider/turn_signal_cmd'), ('input/auto/shift_cmd', '/control/shift_decider/shift_cmd'), - ('input/remote/control_cmd', '/remote/control_cmd'), - ('input/remote/turn_signal_cmd', '/remote/turn_signal_cmd'), - ('input/remote/shift_cmd', '/remote/shift_cmd'), + ('input/remote/control_cmd', '/external/external_cmd_selector/control_cmd'), + ('input/remote/turn_signal_cmd', '/external/external_cmd_selector/turn_signal_cmd'), + ('input/remote/shift_cmd', '/external/external_cmd_selector/shift_cmd'), ('input/emergency/control_cmd', '/system/emergency/control_cmd'), ('input/emergency/turn_signal_cmd', '/system/emergency/turn_signal_cmd'), @@ -206,18 +206,46 @@ def launch_setup(context, *args, **kwargs): }], ) + # external cmd selector + external_cmd_selector_component = ComposableNode( + package='external_cmd_selector', + plugin='ExternalCmdSelector', + name='external_cmd_selector', + remappings=[ + ('~/input/local/raw_control_cmd', '/external/local/raw_control_cmd'), + ('~/input/local/shift_cmd', '/external/local/shift_cmd'), + ('~/input/local/turn_signal_cmd', '/external/local/turn_signal_cmd'), + ('~/input/remote/raw_control_cmd', '/external/remote/raw_control_cmd'), + ('~/input/remote/shift_cmd', '/external/remote/shift_cmd'), + ('~/input/remote/turn_signal_cmd', '/external/remote/turn_signal_cmd'), + ('~/output/current_selector_mode', '~/current_selector_mode'), + ('~/output/raw_control_cmd', '/external/external_cmd_selector/raw_control_cmd'), + ('~/output/shift_cmd', '/external/external_cmd_selector/shift_cmd'), + ('~/output/turn_signal_cmd', '/external/external_cmd_selector/turn_signal_cmd'), + ('~/service/select_external_command', '~/select_external_command'), + ], + parameters=[ + { + 'initial_selector_mode': LaunchConfiguration('initial_selector_mode'), + } + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + # remote cmd converter remote_cmd_converter_component = ComposableNode( package='remote_cmd_converter', plugin='RemoteCmdConverter', name='remote_cmd_converter', remappings=[ - ('in/raw_control_cmd', '/remote/raw_control_cmd'), - ('in/shift_cmd', '/remote/shift_cmd'), + ('in/raw_control_cmd', '/external/external_cmd_selector/raw_control_cmd'), + ('in/shift_cmd', '/external/external_cmd_selector/shift_cmd'), ('in/emergency_stop', '/remote/emergency_stop'), ('in/current_gate_mode', '/control/current_gate_mode'), ('in/twist', '/localization/twist'), - ('out/control_cmd', '/remote/control_cmd'), + ('out/control_cmd', '/external/external_cmd_selector/control_cmd'), ('out/latest_raw_control_cmd', '/remote/latest_raw_control_cmd'), ], parameters=[ @@ -249,6 +277,7 @@ def launch_setup(context, *args, **kwargs): shift_decider_component, vehicle_cmd_gate_component, remote_cmd_converter_component, + external_cmd_selector_component, ], ) @@ -323,6 +352,9 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg('use_emergency_handling', 'false') add_launch_arg('use_external_emergency_stop', 'true') + # external cmd selector + add_launch_arg('initial_selector_mode', '1') + # remote cmd converter add_launch_arg( 'csv_path_accel_map', diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index 394c46ed79..faeae393a5 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -1,5 +1,3 @@ - - @@ -60,8 +58,43 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From c3127cec4c923fe195cb9af0545bf377bb01fd23 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 11 May 2021 11:44:57 +0900 Subject: [PATCH 140/851] Add vehicle info launch for setting vehicle info param (#199) * Add vehicle info launch for setting vehicle info param Signed-off-by: wep21 * Add comment for global parameters section Signed-off-by: wep21 * Fix year and apply format Signed-off-by: Kenji Miyake * Remove ready vehicle info param Signed-off-by: wep21 Co-authored-by: Kenji Miyake --- autoware_launch/launch/autoware.launch.xml | 6 ++++ .../launch/logging_simulator.launch.xml | 6 ++++ .../launch/planning_simulator.launch.xml | 6 ++++ vehicle_launch/launch/vehicle.launch.xml | 7 ---- vehicle_launch/launch/vehicle_info.launch.py | 34 +++++++++++++++++++ 5 files changed, 52 insertions(+), 7 deletions(-) create mode 100644 vehicle_launch/launch/vehicle_info.launch.py diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index e2ac2f6097..109320a704 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -9,6 +9,12 @@ + + + + + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 0f95d3eab8..22ee50bee5 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -21,6 +21,12 @@ + + + + + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index b4d6b9afd4..c6badfbb14 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -20,6 +20,12 @@ + + + + + + diff --git a/vehicle_launch/launch/vehicle.launch.xml b/vehicle_launch/launch/vehicle.launch.xml index 17f9cf8389..b45f4a0f42 100644 --- a/vehicle_launch/launch/vehicle.launch.xml +++ b/vehicle_launch/launch/vehicle.launch.xml @@ -9,13 +9,6 @@ - - - - - - - diff --git a/vehicle_launch/launch/vehicle_info.launch.py b/vehicle_launch/launch/vehicle_info.launch.py new file mode 100644 index 0000000000..22832f7ceb --- /dev/null +++ b/vehicle_launch/launch/vehicle_info.launch.py @@ -0,0 +1,34 @@ +# Copyright 2021 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import SetParameter +import yaml + + +def launch_setup(context, *args, **kwargs): + vehicle_param_file = LaunchConfiguration('config_file').perform(context) + with open(vehicle_param_file, 'r') as f: + vehicle_param = yaml.safe_load(f)['/**']['ros__parameters'] + return [SetParameter(name=k, value=v) for (k, v) in vehicle_param.items()] + + +def generate_launch_description(): + return LaunchDescription([ + DeclareLaunchArgument('config_file'), + OpaqueFunction(function=launch_setup), + ]) From 1e6198b460dbd3b582cb83a84c118650e4a1fd53 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 11 May 2021 12:55:41 +0900 Subject: [PATCH 141/851] Remove vehicle info param server from logging simulator (#211) Signed-off-by: wep21 --- autoware_launch/launch/logging_simulator.launch.xml | 4 ---- 1 file changed, 4 deletions(-) diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 22ee50bee5..149f40e991 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -35,10 +35,6 @@ - - - - From b8331a589aab250b48da4b05b5b146d4bdb6942c Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 12 May 2021 15:21:11 +0900 Subject: [PATCH 142/851] Add container launch for planning (#205) * Add container launch for planning Signed-off-by: wep21 * fix porting miss * fix lane_driving.launch.xml * Add missing parameters Signed-off-by: wep21 Co-authored-by: taichiH --- .../lane_change_planner.param.yaml | 22 ++ .../adaptive_cruise_control.param.yaml | 0 .../obstacle_stop_planner.param.yaml | 0 .../mission_planning.launch.py | 68 +++++ planning_launch/launch/planning.launch.xml | 2 +- .../scenario_planning/lane_driving.launch.xml | 4 +- .../behavior_planning.launch.py | 242 ++++++++++++++++++ .../behavior_planning.launch.xml | 21 +- .../motion_planning/motion_planning.launch.py | 218 ++++++++++++++++ .../motion_planning.launch.xml | 4 +- .../scenario_planning/parking.launch.py | 134 ++++++++++ .../scenario_planning.launch.xml | 2 +- 12 files changed, 691 insertions(+), 26 deletions(-) create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml rename planning_launch/config/{ => scenario_planning/lane_driving/motion_planning/obstacle_stop_planner}/adaptive_cruise_control.param.yaml (100%) rename planning_launch/config/{ => scenario_planning/lane_driving/motion_planning/obstacle_stop_planner}/obstacle_stop_planner.param.yaml (100%) create mode 100644 planning_launch/launch/mission_planning/mission_planning.launch.py create mode 100644 planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py create mode 100644 planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py create mode 100644 planning_launch/launch/scenario_planning/parking.launch.py diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml new file mode 100644 index 0000000000..3e899ca586 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml @@ -0,0 +1,22 @@ +/**: + ros__parameters: + min_stop_distance: 5.0 + stop_time: 2.0 + hysteresis_buffer_distance: 2.0 + backward_path_length: 5.0 + forward_path_length: 200.0 + max_accel: -5.0 + lane_change_prepare_duration: 4.0 + lane_changing_duration: 8.0 + backward_length_buffer_for_end_of_lane: 5.0 + lane_change_finish_judge_buffer: 3.0 + minimum_lane_change_length: 12.0 + minimum_lane_change_velocity: 5.6 + prediction_duration: 8.0 + prediction_time_resolution: 0.5 + drivable_area_resolution: 0.1 + drivable_area_width: 100.0 + drivable_area_height: 50.0 + static_obstacle_velocity_thresh: 1.5 + maximum_deceleration: 1.0 + refine_goal_search_radius_range: 7.5 diff --git a/planning_launch/config/adaptive_cruise_control.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml similarity index 100% rename from planning_launch/config/adaptive_cruise_control.param.yaml rename to planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml diff --git a/planning_launch/config/obstacle_stop_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml similarity index 100% rename from planning_launch/config/obstacle_stop_planner.param.yaml rename to planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml diff --git a/planning_launch/launch/mission_planning/mission_planning.launch.py b/planning_launch/launch/mission_planning/mission_planning.launch.py new file mode 100644 index 0000000000..cef5f74c69 --- /dev/null +++ b/planning_launch/launch/mission_planning/mission_planning.launch.py @@ -0,0 +1,68 @@ +# Copyright 2021 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +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(): + container = ComposableNodeContainer( + name='mission_planning_container', + namespace='', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + ComposableNode( + package='mission_planner', + plugin='mission_planner::MissionPlannerLanelet2', + name='mission_planner', + remappings=[ + ('input/vector_map', '/map/vector_map'), + ('input/goal_pose', '/planning/mission_planning/goal'), + ('input/checkpoint', '/planning/mission_planning/checkpoint'), + ('output/route', '/planning/mission_planning/route'), + ('visualization_topic_name', + '/planning/mission_planning/route_marker'), + ], + parameters=[ + { + 'map_frame': 'map', + 'base_link_frame': 'base_link', + } + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ), + ComposableNode( + package='mission_planner', + plugin='mission_planner::GoalPoseVisualizer', + name='goal_pose_visualizer', + remappings=[ + ('input/route', '/planning/mission_planning/route'), + ('output/goal_pose', + '/planning/mission_planning/echo_back_goal_pose'), + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + ], + ) + return launch.LaunchDescription([ + DeclareLaunchArgument("use_intra_process", default_value='false'), + container + ]) diff --git a/planning_launch/launch/planning.launch.xml b/planning_launch/launch/planning.launch.xml index bfc5e01110..003af6fca8 100644 --- a/planning_launch/launch/planning.launch.xml +++ b/planning_launch/launch/planning.launch.xml @@ -5,7 +5,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..ebceb31b8a 100644 --- a/planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving.launch.xml @@ -6,14 +6,14 @@ - + - + diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py new file mode 100644 index 0000000000..23a9866f70 --- /dev/null +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -0,0 +1,242 @@ +# Copyright 2021 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from ament_index_python.packages import get_package_share_directory +import launch +from launch.actions import DeclareLaunchArgument, SetLaunchConfiguration, ExecuteProcess +from launch.conditions import IfCondition, UnlessCondition +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + +import os +import yaml + + +def generate_launch_description(): + # lane change planner + lane_change_planner_param_path = os.path.join( + get_package_share_directory('planning_launch'), + 'config', + 'scenario_planning', + 'lane_driving', + 'behavior_planning', + 'lane_change_planner', + 'lane_change_planner.param.yaml', + ) + with open(lane_change_planner_param_path, 'r') as f: + lane_change_planner_param = yaml.safe_load(f)['/**']['ros__parameters'] + + lane_change_planner_component = ComposableNode( + package='lane_change_planner', + plugin='lane_change_planner::LaneChanger', + name='lane_change_planner', + namespace='', + remappings=[ + ('~/input/route', LaunchConfiguration('input_route_topic_name')), + ('~/input/vector_map', LaunchConfiguration('map_topic_name')), + ('~/input/perception', '/perception/object_recognition/objects'), + ('~/input/velocity', '/localization/twist'), + ('~/input/lane_change_approval', + '/planning/scenario_planning/lane_driving/lane_change_approval'), + ('~/input/force_lane_change', + '/planning/scenario_planning/lane_driving/force_lane_change'), + ('~/output/lane_change_path', 'path_with_lane_id'), + ('~/output/lane_change_ready', + '/planning/scenario_planning/lane_driving/lane_change_ready'), + ('~/output/lane_change_avialable', + '/planning/scenario_planning/lane_driving/lane_change_available'), + ('~/output/stop_reasons', '/planning/scenario_planning/status/stop_reasons'), + ('~/debug/lane_change_candidate_path', + '/planning/scenario_planning/lane_driving/lane_change_candidate_path'), + ], + parameters=[ + lane_change_planner_param, + { + "enable_abort_lane_change": False, + "enable_collision_check_at_prepare_phase": False, + "use_predicted_path_outside_lanelet": False, + "use_all_predicted_path": False, + "enable_blocked_by_obstacle": False, + } + ], + extra_arguments=[ + {'use_intra_process_comms': LaunchConfiguration('use_intra_process')} + ], + ) + + # turn signal decider + turn_signal_decider_component = ComposableNode( + package='turn_signal_decider', + plugin='turn_signal_decider::TurnSignalDecider', + name='turn_signal_decider', + namespace='', + remappings=[ + ('input/path_with_lane_id', 'path_with_lane_id'), + ('input/vector_map', LaunchConfiguration('map_topic_name')), + ('output/turn_signal_cmd', '/planning/turn_signal_decider/turn_signal_cmd'), + ], + parameters=[ + {'lane_change_search_distance': 30.0}, + {'intersection_search_distance': 30.0}, + ], + extra_arguments=[ + {'use_intra_process_comms': LaunchConfiguration('use_intra_process')} + ], + ) + + # behavior velocity planner + blind_spot_param_path = os.path.join( + get_package_share_directory('behavior_velocity_planner'), + 'config', + 'blind_spot.param.yaml', + ) + with open(blind_spot_param_path, 'r') as f: + blind_spot_param = yaml.safe_load(f)['/**']['ros__parameters'] + + crosswalk_param_path = os.path.join( + get_package_share_directory('behavior_velocity_planner'), + 'config', + 'crosswalk.param.yaml', + ) + with open(crosswalk_param_path, 'r') as f: + crosswalk_param = yaml.safe_load(f)['/**']['ros__parameters'] + + detection_area_param_path = os.path.join( + get_package_share_directory('behavior_velocity_planner'), + 'config', + 'detection_area.param.yaml', + ) + with open(detection_area_param_path, 'r') as f: + detection_area_param = yaml.safe_load(f)['/**']['ros__parameters'] + + intersection_param_path = os.path.join( + get_package_share_directory('behavior_velocity_planner'), + 'config', + 'intersection.param.yaml', + ) + with open(intersection_param_path, 'r') as f: + intersection_param = yaml.safe_load(f)['/**']['ros__parameters'] + + stop_line_param_path = os.path.join( + get_package_share_directory('behavior_velocity_planner'), + 'config', + 'stop_line.param.yaml', + ) + with open(stop_line_param_path, 'r') as f: + stop_line_param = yaml.safe_load(f)['/**']['ros__parameters'] + + traffic_light_param_path = os.path.join( + get_package_share_directory('behavior_velocity_planner'), + 'config', + 'traffic_light.param.yaml', + ) + with open(traffic_light_param_path, 'r') as f: + traffic_light_param = yaml.safe_load(f)['/**']['ros__parameters'] + + behavior_velocity_planner_component = ComposableNode( + package='behavior_velocity_planner', + plugin='BehaviorVelocityPlannerNode', + name='behavior_velocity_planner', + namespace='', + remappings=[ + ('~/input/path_with_lane_id', 'path_with_lane_id'), + ('~/input/vector_map', '/map/vector_map'), + ('~/input/vehicle_velocity', '/localization/twist'), + ('~/input/dynamic_objects', '/perception/object_recognition/objects'), + ('~/input/no_ground_pointcloud', '/sensing/lidar/no_ground/pointcloud'), + ('~/input/traffic_light_states', + '/perception/traffic_light_recognition/traffic_light_states'), + ('~/input/external_traffic_light_states', + '/foa/traffic_light_recognition/traffic_light_states'), + ('~/output/path', 'path'), + ('~/output/stop_reasons', + '/planning/scenario_planning/status/stop_reasons'), + ('~/output/traffic_light_state', 'debug/traffic_light_state'), + ], + parameters=[ + { + 'launch_stop_line': True, + 'launch_crosswalk': True, + 'launch_traffic_light': True, + 'launch_intersection': True, + 'launch_blind_spot': True, + 'launch_detection_area': True, + 'forward_path_length': 1000.0, + 'backward_path_length': 5.0, + 'max_accel': -2.8, + 'delay_response_time': 1.3 + }, + blind_spot_param, + crosswalk_param, + detection_area_param, + intersection_param, + stop_line_param, + traffic_light_param + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + container = ComposableNodeContainer( + name='behavior_planning_container', + namespace='', + package='rclcpp_components', + executable=LaunchConfiguration('container_executable'), + composable_node_descriptions=[ + lane_change_planner_component, + turn_signal_decider_component, + behavior_velocity_planner_component, + ], + output='screen', + ) + + set_container_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container', + condition=UnlessCondition(LaunchConfiguration('use_multithread')), + ) + set_container_mt_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container_mt', + condition=IfCondition(LaunchConfiguration('use_multithread')), + ) + + return launch.LaunchDescription([ + DeclareLaunchArgument( + 'input_route_topic_name', + default_value='/planning/mission_planning/route'), + DeclareLaunchArgument( + 'map_topic_name', + default_value='/map/vector_map' + ), + DeclareLaunchArgument( + 'use_intra_process', + default_value='false' + ), + DeclareLaunchArgument( + 'use_multithread', + default_value='false' + ), + set_container_executable, + set_container_mt_executable, + container, + ExecuteProcess( + cmd=['ros2', 'topic', 'pub', + '/planning/scenario_planning/lane_driving/lane_change_approval', + 'autoware_planning_msgs/msg/LaneChangeCommand', '{command: true}', + '-r', '10']), + ]) 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 7a4734fb9d..708fe5158d 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 @@ -14,30 +14,11 @@ - - - - - - - - - - - - - - - - - - - + - diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py new file mode 100644 index 0000000000..b5caf17fe2 --- /dev/null +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -0,0 +1,218 @@ +# Copyright 2021 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from ament_index_python.packages import get_package_share_directory +import launch +from launch.actions import DeclareLaunchArgument, SetLaunchConfiguration +from launch.conditions import IfCondition, UnlessCondition +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch_ros.descriptions import ComposableNode + +import os +import yaml + + +def generate_launch_description(): + # obstacle avoidance planner + obstacle_avoidance_planner_param_path = os.path.join( + get_package_share_directory('planning_launch'), + 'config', + 'scenario_planning', + 'lane_driving', + 'motion_planning', + 'obstacle_avoidance_planner', + 'obstacle_avoidance_planner.param.yaml', + ) + with open(obstacle_avoidance_planner_param_path, 'r') as f: + obstacle_avoidance_planner_param = yaml.safe_load(f)['/**']['ros__parameters'] + obstacle_avoidance_planner_component = ComposableNode( + package='obstacle_avoidance_planner', + plugin='ObstacleAvoidancePlanner', + name='obstacle_avoidance_planner', + namespace='', + remappings=[ + ('~/input/objects', '/perception/object_recognition/objects'), + ('~/input/path', LaunchConfiguration('input_path_topic')), + ('~/output/path', 'obstacle_avoidance_planner/trajectory'), + ], + parameters=[ + obstacle_avoidance_planner_param, + {'is_showing_debug_info': False}, + {'is_stopping_if_outside_drivable_area': True}, + ], + extra_arguments=[ + {'use_intra_process_comms': LaunchConfiguration('use_intra_process')} + ], + ) + + # surround obstacle checker + surround_obstacle_checker_param_path = os.path.join( + get_package_share_directory('planning_launch'), + 'config', + 'scenario_planning', + 'lane_driving', + 'motion_planning', + 'surround_obstacle_checker', + 'surround_obstacle_checker.param.yaml', + ) + with open(surround_obstacle_checker_param_path, 'r') as f: + surround_obstacle_checker_param = yaml.safe_load(f)['/**']['ros__parameters'] + surround_obstacle_checker_component = ComposableNode( + package='surround_obstacle_checker', + plugin='SurroundObstacleCheckerNode', + name='surround_obstacle_checker', + namespace='', + remappings=[ + ('~/output/no_start_reason', + '/planning/scenario_planning/status/no_start_reason'), + ('~/output/stop_reasons', + '/planning/scenario_planning/status/stop_reasons'), + ('~/output/trajectory', 'surround_obstacle_checker/trajectory'), + ('~/input/pointcloud', '/sensing/lidar/no_ground/pointcloud'), + ('~/input/objects', '/perception/object_recognition/objects'), + ('~/input/twist', '/localization/twist'), + ('~/input/trajectory', 'obstacle_avoidance_planner/trajectory'), + ], + parameters=[ + surround_obstacle_checker_param, + ], + extra_arguments=[ + {'use_intra_process_comms': LaunchConfiguration('use_intra_process')} + ], + ) + + # relay + relay_component = ComposableNode( + package='topic_tools', + plugin='topic_tools::RelayNode', + name='skip_surround_obstacle_check_relay', + namespace='', + parameters=[{ + 'input_topic': 'obstacle_avoidance_planner/trajectory', + 'output_topic': 'surround_obstacle_checker/trajectory', + 'type': 'autoware_planning_msgs/msg/Trajectory', + }], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + # obstacle stop planner + obstacle_stop_planner_param_path = os.path.join( + get_package_share_directory('planning_launch'), + 'config', + 'scenario_planning', + 'lane_driving', + 'motion_planning', + 'obstacle_stop_planner', + 'obstacle_stop_planner.param.yaml', + ) + obstacle_stop_planner_acc_param_path = os.path.join( + get_package_share_directory('planning_launch'), + 'config', + 'scenario_planning', + 'lane_driving', + 'motion_planning', + 'obstacle_stop_planner', + 'adaptive_cruise_control.param.yaml', + ) + with open(obstacle_stop_planner_param_path, 'r') as f: + obstacle_stop_planner_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(obstacle_stop_planner_acc_param_path, 'r') as f: + obstacle_stop_planner_acc_param = yaml.safe_load(f)['/**']['ros__parameters'] + obstacle_stop_planner_component = ComposableNode( + package='obstacle_stop_planner', + plugin='motion_planning::ObstacleStopPlannerNode', + name='obstacle_stop_planner', + namespace='', + remappings=[ + ('~/output/stop_reason', + '/planning/scenario_planning/status/stop_reason'), + ('~/output/stop_reasons', + '/planning/scenario_planning/status/stop_reasons'), + ('~/output/trajectory', + '/planning/scenario_planning/lane_driving/trajectory'), + ('~/input/pointcloud', '/sensing/lidar/no_ground/pointcloud'), + ('~/input/objects', '/perception/object_recognition/objects'), + ('~/input/twist', '/localization/twist'), + ('~/input/trajectory', 'surround_obstacle_checker/trajectory'), + ], + parameters=[ + obstacle_stop_planner_param, + obstacle_stop_planner_acc_param, + {'enable_slow_down': False} + ], + extra_arguments=[ + {'use_intra_process_comms': LaunchConfiguration('use_intra_process')} + ], + ) + + container = ComposableNodeContainer( + name='motion_planning_container', + namespace='', + package='rclcpp_components', + executable=LaunchConfiguration('container_executable'), + composable_node_descriptions=[ + obstacle_avoidance_planner_component, + obstacle_stop_planner_component + ], + ) + + surround_obstacle_checker_loader = LoadComposableNodes( + composable_node_descriptions=[surround_obstacle_checker_component], + target_container=container, + condition=IfCondition(LaunchConfiguration('use_surround_obstacle_check')), + ) + + relay_loader = LoadComposableNodes( + composable_node_descriptions=[relay_component], + target_container=container, + condition=UnlessCondition(LaunchConfiguration('use_surround_obstacle_check')), + ) + + set_container_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container', + condition=UnlessCondition(LaunchConfiguration('use_multithread')), + ) + set_container_mt_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container_mt', + condition=IfCondition(LaunchConfiguration('use_multithread')), + ) + + return launch.LaunchDescription([ + DeclareLaunchArgument( + 'input_path_topic', + default_value='/planning/scenario_planning/lane_driving/behavior_planning/path'), + DeclareLaunchArgument( + 'use_surround_obstacle_check', + default_value='true' + ), + DeclareLaunchArgument( + 'use_intra_process', + default_value='false' + ), + DeclareLaunchArgument( + 'use_multithread', + default_value='false' + ), + set_container_executable, + set_container_mt_executable, + container, + surround_obstacle_checker_loader, + relay_loader, + ]) 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 7b26011fa4..05892f5a25 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 @@ -36,8 +36,8 @@ - - + + diff --git a/planning_launch/launch/scenario_planning/parking.launch.py b/planning_launch/launch/scenario_planning/parking.launch.py new file mode 100644 index 0000000000..aefe6f414d --- /dev/null +++ b/planning_launch/launch/scenario_planning/parking.launch.py @@ -0,0 +1,134 @@ +# Copyright 2021 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +import launch +from launch.actions import DeclareLaunchArgument, GroupAction, SetLaunchConfiguration +from launch.conditions import IfCondition, UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer, PushRosNamespace +from launch_ros.descriptions import ComposableNode + + +def generate_launch_description(): + container = ComposableNodeContainer( + name='parking_container', + namespace='', + package='rclcpp_components', + executable=LaunchConfiguration('container_executable'), + composable_node_descriptions=[ + ComposableNode( + package='costmap_generator', + plugin='CostmapGenerator', + name='costmap_generator', + remappings=[ + ('~/input/objects', '/perception/object_recognition/objects'), + ('~/input/points_no_ground', '/sensing/lidar/no_ground/pointcloud'), + ('~/input/vector_map', '/map/vector_map'), + ('~/input/scenario', '/planning/scenario_planning/scenario'), + ('~/output/grid_map', 'costmap_generator/grid_map'), + ('~/output/occupancy_grid', 'costmap_generator/occupancy_grid'), + ], + parameters=[ + { + 'costmap_frame': 'map', + 'vehicle_frame': 'base_link', + 'map_frame': 'map', + 'update_rate': 10.0, + 'use_wayarea': True, + 'use_objects': True, + 'use_points': True, + 'grid_min_value': 0.0, + 'grid_max_value': 1.0, + 'grid_resolution': 0.2, + 'grid_length_x': 70.0, + 'grid_length_y': 70.0, + 'grid_position_x': 0.0, + 'grid_position_y': 0.0, + 'maximum_lidar_height_thres': 0.3, + 'minimum_lidar_height_thres': -2.2, + 'expand_polygon_size': 1.0, + 'size_of_expansion_kernel': 9, + }, + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ), + ComposableNode( + package='freespace_planner', + plugin='AstarNavi', + name='freespace_planner', + remappings=[ + ('~/input/route', '/planning/mission_planning/route'), + ('~/input/occupancy_grid', 'costmap_generator/occupancy_grid'), + ('~/input/scenario', '/planning/scenario_planning/scenario'), + ('~/input/twist', '/localization/twist'), + ('~/output/trajectory', + '/planning/scenario_planning/parking/trajectory'), + ('is_completed', '/planning/scenario_planning/parking/is_completed'), + ], + parameters=[ + { + 'waypoints_velocity': 5.0, + 'update_rate': 10.0, + 'th_arrived_distance_m': 1.0, + 'th_stopped_time_sec': 1.0, + 'th_stopped_velocity_mps': 0.01, + 'th_course_out_distance_m': 1.0, + 'replan_when_obstacle_found': True, + 'replan_when_course_out': True, + 'use_back': True, + 'only_behind_solutions': False, + 'time_limit': 30000.0, + 'robot_length': 4.5, + 'robot_width': 1.75, + 'robot_base2back': 1.0, + 'minimum_turning_radius': 9.0, + 'theta_size': 144, + 'angle_goal_range': 6.0, + 'curve_weight': 1.2, + 'reverse_weight': 2.0, + 'lateral_goal_range': 0.5, + 'longitudinal_goal_range': 2.0, + 'obstacle_threshold': 100, + 'distance_heuristic_weight': 1.0, + }, + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + ], + ) + + set_container_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container', + condition=UnlessCondition(LaunchConfiguration('use_multithread')), + ) + set_container_mt_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container_mt', + condition=IfCondition(LaunchConfiguration('use_multithread')), + ) + + return launch.LaunchDescription([ + DeclareLaunchArgument("use_intra_process", default_value='false'), + DeclareLaunchArgument("use_multithread", default_value='false'), + set_container_executable, + set_container_mt_executable, + GroupAction([ + PushRosNamespace('parking'), + container + ]) + ]) diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 469e147447..0d80c87faf 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -28,7 +28,7 @@ - + From 500ea1104dbb8ea99325c8486c13d8113b7650f8 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 13 May 2021 15:47:31 +0900 Subject: [PATCH 143/851] Add map.launch.py (#212) * Add map.launch.py Signed-off-by: wep21 * Update map.launch.xml Signed-off-by: wep21 * Rename parameter for lanelet2 map path Signed-off-by: wep21 --- autoware_launch/launch/autoware.launch.xml | 2 +- .../launch/logging_simulator.launch.xml | 2 +- .../launch/planning_simulator.launch.xml | 2 +- map_launch/launch/map.launch.py | 121 ++++++++++++++++++ map_launch/launch/map.launch.xml | 5 +- 5 files changed, 127 insertions(+), 5 deletions(-) create mode 100644 map_launch/launch/map.launch.py diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 109320a704..b36abfc84c 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -28,7 +28,7 @@ - + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 149f40e991..ca1784889d 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -47,7 +47,7 @@ - + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index c6badfbb14..3abbf6bf4f 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -42,7 +42,7 @@ - + diff --git a/map_launch/launch/map.launch.py b/map_launch/launch/map.launch.py new file mode 100644 index 0000000000..1d0712b32c --- /dev/null +++ b/map_launch/launch/map.launch.py @@ -0,0 +1,121 @@ +# Copyright 2021 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import launch +from launch.actions import DeclareLaunchArgument, GroupAction, SetLaunchConfiguration +from launch.conditions import IfCondition, UnlessCondition +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import ComposableNodeContainer, PushRosNamespace +from launch_ros.descriptions import ComposableNode + + +def generate_launch_description(): + lanelet2_map_loader = ComposableNode( + package='map_loader', + plugin='Lanelet2MapLoaderNode', + name='lanelet2_map_loader', + remappings=[('output/lanelet2_map', 'vector_map')], + parameters=[ + { + 'center_line_resolution': 5.0, + 'lanelet2_map_path': LaunchConfiguration('lanelet2_map_path'), + } + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + lanelet2_map_visualization = ComposableNode( + package='map_loader', + plugin='Lanelet2MapVisualizationNode', + name='lanelet2_map_visualization', + remappings=[('input/lanelet2_map', 'vector_map'), + ('output/lanelet2_map_marker', 'vector_map_marker')], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + pointcloud_map_loader = ComposableNode( + package='map_loader', + plugin='PointCloudMapLoaderNode', + name='pointcloud_map_loader', + remappings=[('output/pointcloud_map', 'pointcloud_map')], + parameters=[ + { + 'pcd_paths_or_directory': ['[', LaunchConfiguration('pointcloud_map_path'), ']'] + } + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + map_tf_generator = ComposableNode( + package='map_tf_generator', + plugin='MapTFGeneratorNode', + name='map_tf_generator', + parameters=[ + { + 'map_frame': 'map', + 'viewer_frame': 'viewer', + } + ], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ) + + container = ComposableNodeContainer( + name='map_container', + namespace='', + package='rclcpp_components', + executable=LaunchConfiguration('container_executable'), + composable_node_descriptions=[ + lanelet2_map_loader, + lanelet2_map_visualization, + pointcloud_map_loader, + map_tf_generator, + ], + output='screen', + ) + + def add_launch_arg(name: str, default_value=None): + return DeclareLaunchArgument(name, default_value=default_value) + + return launch.LaunchDescription([ + add_launch_arg('map_path', ''), + add_launch_arg('lanelet2_map_path', [ + LaunchConfiguration('map_path'), '/lanelet2_map.osm']), + add_launch_arg('pointcloud_map_path', [ + LaunchConfiguration('map_path'), '/pointcloud_map.pcd']), + add_launch_arg('use_intra_process', 'false'), + add_launch_arg('use_multithread', 'false'), + SetLaunchConfiguration( + 'container_executable', + 'component_container', + condition=UnlessCondition(LaunchConfiguration('use_multithread')) + ), + SetLaunchConfiguration( + 'container_executable', + 'component_container_mt', + condition=IfCondition(LaunchConfiguration('use_multithread')) + ), + GroupAction([ + PushRosNamespace('map'), + container, + ]) + ]) diff --git a/map_launch/launch/map.launch.xml b/map_launch/launch/map.launch.xml index 2d792eb3fe..5bedbc1d56 100644 --- a/map_launch/launch/map.launch.xml +++ b/map_launch/launch/map.launch.xml @@ -6,11 +6,12 @@ - + - + + From 9f6555ac49cbd81484beb5fa047ffa6f928fe975 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Fri, 14 May 2021 14:14:37 +0900 Subject: [PATCH 144/851] Rename AstarNavi to FreespacePlannerNode (#213) Signed-off-by: Kenji Miyake --- planning_launch/launch/scenario_planning/parking.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/launch/scenario_planning/parking.launch.py b/planning_launch/launch/scenario_planning/parking.launch.py index aefe6f414d..4a83f7a0bb 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.py +++ b/planning_launch/launch/scenario_planning/parking.launch.py @@ -66,7 +66,7 @@ def generate_launch_description(): ), ComposableNode( package='freespace_planner', - plugin='AstarNavi', + plugin='FreespacePlannerNode', name='freespace_planner', remappings=[ ('~/input/route', '/planning/mission_planning/route'), From 53fd6a1f76012441fc3d43a7102c06ed7eab5815 Mon Sep 17 00:00:00 2001 From: Kazuki Miyahara Date: Fri, 14 May 2021 18:57:38 +0900 Subject: [PATCH 145/851] Add spell check action (#214) --- .github/workflows/spell_check_pr.yaml | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) create mode 100644 .github/workflows/spell_check_pr.yaml diff --git a/.github/workflows/spell_check_pr.yaml b/.github/workflows/spell_check_pr.yaml new file mode 100644 index 0000000000..c6c3c6c3da --- /dev/null +++ b/.github/workflows/spell_check_pr.yaml @@ -0,0 +1,23 @@ +name: Check spelling + +on: + pull_request: + branches: + - main + +jobs: + spellcheck: + runs-on: ubuntu-latest + steps: + - name: Checkout repository + uses: actions/checkout@v2 + + - name: Retrieve spell check dictionary + run: | + curl --silent --show-error \ + --output .github/workflows/.cspell.json \ + https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json + + - uses: streetsidesoftware/cspell-action@v1.1.1 + with: + config: ".github/workflows/.cspell.json" From 86fa9226780c0b6312f13f0642384cf486132775 Mon Sep 17 00:00:00 2001 From: Kazuki Miyahara Date: Tue, 18 May 2021 18:44:32 +0900 Subject: [PATCH 146/851] Unify YAML file extension of GitHub action to yml (#216) --- .github/workflows/{spell_check_pr.yaml => spell_check_pr.yml} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename .github/workflows/{spell_check_pr.yaml => spell_check_pr.yml} (100%) diff --git a/.github/workflows/spell_check_pr.yaml b/.github/workflows/spell_check_pr.yml similarity index 100% rename from .github/workflows/spell_check_pr.yaml rename to .github/workflows/spell_check_pr.yml From 31e448655f0d31a4d4f3463d393439828024bb91 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Wed, 19 May 2021 22:07:08 +0900 Subject: [PATCH 147/851] Fix PR template (#218) Signed-off-by: Kenji Miyake --- .github/PULL_REQUEST_TEMPLATE.md | 46 +++++++++++++++++++++++++------- 1 file changed, 37 insertions(+), 9 deletions(-) diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md index 30faaaeaba..5e57e4f29c 100644 --- a/.github/PULL_REQUEST_TEMPLATE.md +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -1,15 +1,43 @@ -## PRの種類 +## PR Type -- [ ] 新機能 -- [ ] 既存機能の性能向上 -- [ ] バグフィックス + -## Jiraリンク +- New Feature +- Improvement +- Bug Fix -## 変更概要 +## Related Links -## レビュー方法 + -## その他 +## Description -- [ ] [リリースノート](https://tier4.atlassian.net/wiki/spaces/AIP/pages/563774416)への記載 + + +## Review Procedure + + + +## Remarks + + + +## Pre-Review Checklist for the PR Author + +- [ ] Code follows [coding guidelines](coding-guidelines) +- [ ] Assign PR to reviewer + +## Checklist for the PR Reviewer + +- [ ] Commits are properly organized and messages are according to the guideline +- [ ] Code follows [coding guidelines](coding-guidelines) +- [ ] (Optional) Unit tests have been written for new behavior +- [ ] PR title describes the changes + +## Post-review Checklist for the PR Author + +- [ ] All open points are addressed and tracked via issues or tickets +- [ ] Write [release notes](release-notes) + +[coding-guidelines]: https://tier4.atlassian.net/wiki/spaces/AIP/pages/1194394777/T4 +[release-notes]: https://tier4.atlassian.net/wiki/spaces/AIP/pages/563774416 From 234d88c2357b15289e4b821ac0d9c24ed4e99ac3 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Wed, 19 May 2021 22:21:10 +0900 Subject: [PATCH 148/851] Fix PR template link (#219) Signed-off-by: Kenji Miyake --- .github/PULL_REQUEST_TEMPLATE.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md index 5e57e4f29c..a685fd932d 100644 --- a/.github/PULL_REQUEST_TEMPLATE.md +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -24,20 +24,20 @@ ## Pre-Review Checklist for the PR Author -- [ ] Code follows [coding guidelines](coding-guidelines) +- [ ] Code follows [coding guidelines][coding-guidelines] - [ ] Assign PR to reviewer ## Checklist for the PR Reviewer - [ ] Commits are properly organized and messages are according to the guideline -- [ ] Code follows [coding guidelines](coding-guidelines) +- [ ] Code follows [coding guidelines][coding-guidelines] - [ ] (Optional) Unit tests have been written for new behavior - [ ] PR title describes the changes ## Post-review Checklist for the PR Author - [ ] All open points are addressed and tracked via issues or tickets -- [ ] Write [release notes](release-notes) +- [ ] Write [release notes][release-notes] [coding-guidelines]: https://tier4.atlassian.net/wiki/spaces/AIP/pages/1194394777/T4 [release-notes]: https://tier4.atlassian.net/wiki/spaces/AIP/pages/563774416 From a5797a0bb6c29ff736f2b83f27704a897f78acc2 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Thu, 20 May 2021 11:38:29 +0900 Subject: [PATCH 149/851] Fix minor typos in PULL_REQUEST_TEMPLATE.md (#222) --- .github/PULL_REQUEST_TEMPLATE.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md index a685fd932d..60b1122dae 100644 --- a/.github/PULL_REQUEST_TEMPLATE.md +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -12,7 +12,7 @@ ## Description - + ## Review Procedure @@ -20,7 +20,7 @@ ## Remarks - + ## Pre-Review Checklist for the PR Author @@ -34,7 +34,7 @@ - [ ] (Optional) Unit tests have been written for new behavior - [ ] PR title describes the changes -## Post-review Checklist for the PR Author +## Post-Review Checklist for the PR Author - [ ] All open points are addressed and tracked via issues or tickets - [ ] Write [release notes][release-notes] From cbf7440ee413685e6d1f6c0bcbc224e5b408ad7c Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Thu, 20 May 2021 14:36:52 +0900 Subject: [PATCH 150/851] Fix depends in localization_launch to exec_depend (#223) Signed-off-by: Kenji Miyake --- localization_launch/package.xml | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/localization_launch/package.xml b/localization_launch/package.xml index 3dc295d636..8ac75637ba 100644 --- a/localization_launch/package.xml +++ b/localization_launch/package.xml @@ -11,12 +11,12 @@ ament_cmake_auto - ndt_scan_matcher - ekf_localizer - gyro_odometer - pose_initializer - pointcloud_preprocessor - topic_tools + ndt_scan_matcher + ekf_localizer + gyro_odometer + pose_initializer + pointcloud_preprocessor + topic_tools ament_lint_auto ament_lint_common From 5cd054ac9ba8278c8ff37f95800231e3e6ae5af9 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Fri, 21 May 2021 09:28:42 +0900 Subject: [PATCH 151/851] Add build CI (#224) * Add build CI Signed-off-by: Kenji Miyake * Fix build_depend.repos Signed-off-by: Kenji Miyake * Add private repository settings Signed-off-by: Kenji Miyake * Remove self repo Signed-off-by: Kenji Miyake * Install pip Signed-off-by: Kenji Miyake * Use packages-select and packages-up-to Signed-off-by: Kenji Miyake * Change job name Signed-off-by: Kenji Miyake * Add build_and_test.yml Signed-off-by: Kenji Miyake * Install kvaser library Signed-off-by: Kenji Miyake --- .github/workflows/build_and_test.yml | 118 +++++++++++----------- .github/workflows/build_and_test_pr.yml | 94 +++++++++++++++++ .github/workflows/get_modified_package.sh | 62 ++++++++++++ build_depends.repos | 53 ---------- 4 files changed, 214 insertions(+), 113 deletions(-) create mode 100644 .github/workflows/build_and_test_pr.yml create mode 100755 .github/workflows/get_modified_package.sh delete mode 100644 build_depends.repos diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index cfb1ed8fc2..f118657f74 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -1,73 +1,71 @@ name: Build and test on: - pull_request: - branches: - - ros2 - - ros2-v0.8.0-beta - push: - branches: - - ros2 - - ros2-v0.8.0-beta + schedule: + - cron: "0 19 * * *" # run at 4 AM JST + workflow_dispatch: + +env: + BUILD_DEPEND_FILE: https://raw.githubusercontent.com/tier4/autoware.proj/main/autoware.proj.repos + SELF_REPO: tier4/autoware_launcher jobs: build-and-test: runs-on: ubuntu-latest - container: ros:foxy + container: osrf/ros:foxy-desktop steps: - - name: Check out repo - uses: actions/checkout@v2 + - name: Checkout repository + uses: actions/checkout@v2 + + - name: Install pip + run: | + apt-get -y update + apt-get -y install python3-pip + + - name: Install kvaser library + run: | + apt-get -y update + apt-get -y install software-properties-common + add-apt-repository ppa:astuff/kvaser-linux + apt-get -y update + apt-get -y install kvaser-canlib-dev kvaser-drivers-dkms + + - name: Install yq + run: | + apt-get -y update + apt-get -y install wget + wget -O /usr/local/bin/yq https://github.com/mikefarah/yq/releases/download/v4.9.1/yq_linux_amd64 + chmod +x /usr/local/bin/yq + + - name: Create build_depends.repos + run: | + curl -sSL -H "Authorization: token ${{ secrets.REPO_TOKEN }}" ${{ env.BUILD_DEPEND_FILE }} | sed -e "s|git@github.com:|https://github.com/|g" > build_depends.repos + repo_key=$(grep ${{ env.SELF_REPO }} build_depends.repos -B2 | grep ":\$" | sed -r 's|\s+([a-zA-Z/]+):|\1|g') + echo "Remove $repo_key from build_depends.repos" + yq eval --inplace "del(.repositories.${repo_key})" build_depends.repos - - name: Clone dependency packages - run: | - mkdir dependency_ws - vcs import dependency_ws < build_depends.repos + - name: Set git config for private repositories + run: | + git config --local --unset-all http.https://github.com/.extraheader || true + git config --global url.https://${{ secrets.REPO_TOKEN }}@github.com.insteadof 'https://github.com' - - name: Install missing dependencies - run: | - 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: Clone dependency packages + run: | + mkdir dependency_ws + vcs import dependency_ws < build_depends.repos + apt-get -y update + rosdep update + rosdep install -y --from-paths . --ignore-src --rosdistro foxy - - name: Build - run: | - . /opt/ros/foxy/setup.sh - colcon build \ - --event-handlers console_cohesion+ \ - --packages-ignore \ - autoware_launch \ - integration_launch \ - perception_launch \ - planning_launch \ - sensing_launch \ - --packages-up-to \ - control_launch \ - map_launch \ - system_launch \ - vehicle_launch \ - localization_launch + - name: Build + run: | + . /opt/ros/foxy/setup.sh + colcon build --event-handlers console_cohesion+ \ + --cmake-args -DCMAKE_BUILD_TYPE=Release - - name: Run tests - run: | - . /opt/ros/foxy/setup.sh - colcon test \ - --return-code-on-test-failure \ - --event-handlers console_cohesion+ \ - --packages-ignore \ - autoware_launch \ - integration_launch \ - perception_launch \ - planning_launch \ - sensing_launch \ - --packages-up-to \ - control_launch \ - map_launch \ - system_launch \ - vehicle_launch \ - localization_launch + - name: Run tests + run: | + . /opt/ros/foxy/setup.sh + colcon test --event-handlers console_cohesion+ \ + --return-code-on-test-failure diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml new file mode 100644 index 0000000000..2564bf7579 --- /dev/null +++ b/.github/workflows/build_and_test_pr.yml @@ -0,0 +1,94 @@ +name: Build and test for PR + +on: + pull_request: + branches: + - main + workflow_dispatch: + +env: + BUILD_DEPEND_FILE: https://raw.githubusercontent.com/tier4/autoware.proj/main/autoware.proj.repos + SELF_REPO: tier4/autoware_launcher + +jobs: + build-and-test-pr: + runs-on: ubuntu-latest + container: osrf/ros:foxy-desktop + + steps: + - name: Cancel previous runs + uses: styfle/cancel-workflow-action@0.9.0 + + - name: Checkout repository + uses: actions/checkout@v2 + with: + fetch-depth: 0 + + - name: Install pip + run: | + apt-get -y update + apt-get -y install python3-pip + + - name: Install kvaser library + run: | + apt-get -y update + apt-get -y install software-properties-common + add-apt-repository ppa:astuff/kvaser-linux + apt-get -y update + apt-get -y install kvaser-canlib-dev kvaser-drivers-dkms + + - name: Search modified package + id: list_packages + run: | + ${GITHUB_WORKSPACE}/.github/workflows/get_modified_package.sh + + - name: Show target packages + run: | + echo "Target packages: ${{ steps.list_packages.outputs.package_list }}" + + - name: Install yq + if: ${{ steps.list_packages.outputs.package_list != '' }} + run: | + apt-get -y update + apt-get -y install wget + wget -O /usr/local/bin/yq https://github.com/mikefarah/yq/releases/download/v4.9.1/yq_linux_amd64 + chmod +x /usr/local/bin/yq + + - name: Create build_depends.repos + if: ${{ steps.list_packages.outputs.package_list != '' }} + run: | + curl -sSL -H "Authorization: token ${{ secrets.REPO_TOKEN }}" ${{ env.BUILD_DEPEND_FILE }} | sed -e "s|git@github.com:|https://github.com/|g" > build_depends.repos + repo_key=$(grep ${{ env.SELF_REPO }} build_depends.repos -B2 | grep ":\$" | sed -r 's|\s+([a-zA-Z/]+):|\1|g') + echo "Remove $repo_key from build_depends.repos" + yq eval --inplace "del(.repositories.${repo_key})" build_depends.repos + + - name: Set git config for private repositories + if: ${{ steps.list_packages.outputs.package_list != '' }} + run: | + git config --local --unset-all http.https://github.com/.extraheader || true + git config --global url.https://${{ secrets.REPO_TOKEN }}@github.com.insteadof 'https://github.com' + + - name: Clone dependency packages + if: ${{ steps.list_packages.outputs.package_list != '' }} + run: | + mkdir dependency_ws + vcs import dependency_ws < build_depends.repos + apt-get -y update + rosdep update + rosdep install -y --from-paths . --ignore-src --rosdistro foxy + + - name: Build + if: ${{ steps.list_packages.outputs.package_list != '' }} + run: | + . /opt/ros/foxy/setup.sh + colcon build --event-handlers console_cohesion+ \ + --packages-up-to ${{ steps.list_packages.outputs.package_list }} \ + --cmake-args -DCMAKE_BUILD_TYPE=Release + + - name: Run tests + if: ${{ steps.list_packages.outputs.package_list != '' }} + run: | + . /opt/ros/foxy/setup.sh + colcon test --event-handlers console_cohesion+ \ + --packages-select ${{ steps.list_packages.outputs.package_list }} \ + --return-code-on-test-failure diff --git a/.github/workflows/get_modified_package.sh b/.github/workflows/get_modified_package.sh new file mode 100755 index 0000000000..696d112d36 --- /dev/null +++ b/.github/workflows/get_modified_package.sh @@ -0,0 +1,62 @@ +#!/bin/bash +# Search for packages that have been modified from the main branch. + +set -e + +SCRIPT_DIR=$(cd $(dirname $0); pwd) +ROOT_DIR=$(readlink -f $SCRIPT_DIR/../../) + +function get_package_name_from_xml() { + [ "$1" == "" ] && return 1 + + # Get tag in package.xml + sed -rz "s|.*\s*([a-zA-Z_0-9]+)\s*.*|\1|" < "$1" + + return 0 +} + +function find_package_from_file() { + [ "$1" == "" ] && return 1 + + target_dir=$(dirname $1) + while true ; do + parent_dir=$(dirname "$target_dir") + + # Exit if no parent found + if [ "$parent_dir" = "$target_dir" ] ; then + return 0 + fi + + # Output package name if package.xml found + if [ -f "$target_dir/package.xml" ] ; then + get_package_name_from_xml "$target_dir"/package.xml + return 0 + fi + + # Move to parent dir + target_dir=$parent_dir + done + + return 1 +} + +# Find modified files after merging origin/main +merge_base=$(git merge-base HEAD origin/main) +modified_files=$(git diff --name-only "$merge_base") + +# Find modified packages +for modified_file in $modified_files; do + modified_package=$(find_package_from_file "$ROOT_DIR/$modified_file") + + if [ "$modified_package" != "" ] ; then + modified_packages="$modified_packages $modified_package" + fi +done + +# Remove duplicates +# shellcheck disable=SC2086 +unique_modified_packages=$(printf "%s\n" $modified_packages | sort | uniq) + +# Output +# shellcheck disable=SC2086 +echo ::set-output name=package_list::$unique_modified_packages diff --git a/build_depends.repos b/build_depends.repos deleted file mode 100644 index c8f3899819..0000000000 --- a/build_depends.repos +++ /dev/null @@ -1,53 +0,0 @@ -repositories: - dependencies/AutowareArchitectureProposal.iv: - type: git - url: https://github.com/tier4/AutowareArchitectureProposal.iv.git - version: ros2 - 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 - 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 - vendor/tamagawa_imu_driver: - type: git - url: https://github.com/tier4/tamagawa_imu_driver.git - version: ros2 - vendor/livox-driver: - type: git - url: https://github.com/Livox-SDK/livox_ros2_driver.git - version: master - vendor/usb_cam: - type: git - url: https://github.com/tier4/usb_cam.git - version: tier4/ros2 - 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 - vendor/clock_publisher: - type: git - url: https://github.com/mitsudome-r/clock_publisher.git - version: master \ No newline at end of file From 2e38a3add726908f37a8aa6a00c9db9edda02d5e Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 24 May 2021 15:38:02 +0900 Subject: [PATCH 152/851] Build only internal packages in CI (#227) Signed-off-by: Kenji Miyake --- .github/workflows/build_and_test.yml | 11 +++++++++++ .github/workflows/build_and_test_pr.yml | 1 + 2 files changed, 12 insertions(+) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index f118657f74..369290930d 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -31,6 +31,15 @@ jobs: apt-get -y update apt-get -y install kvaser-canlib-dev kvaser-drivers-dkms + - name: Search modified package + id: list_packages + run: | + echo ::set-output name=package_list::$(colcon list --names-only) + + - name: Show target packages + run: | + echo "Target packages: ${{ steps.list_packages.outputs.package_list }}" + - name: Install yq run: | apt-get -y update @@ -62,10 +71,12 @@ jobs: run: | . /opt/ros/foxy/setup.sh colcon build --event-handlers console_cohesion+ \ + --packages-up-to ${{ steps.list_packages.outputs.package_list }} \ --cmake-args -DCMAKE_BUILD_TYPE=Release - name: Run tests run: | . /opt/ros/foxy/setup.sh colcon test --event-handlers console_cohesion+ \ + --packages-select ${{ steps.list_packages.outputs.package_list }} \ --return-code-on-test-failure diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml index 2564bf7579..cede36fb75 100644 --- a/.github/workflows/build_and_test_pr.yml +++ b/.github/workflows/build_and_test_pr.yml @@ -22,6 +22,7 @@ jobs: - name: Checkout repository uses: actions/checkout@v2 with: + # Fetch with depth=0 to calculate modified packages fetch-depth: 0 - name: Install pip From 60484ab944e7e1ac9ca5ebb25a247cb696426926 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 24 May 2021 22:33:51 +0900 Subject: [PATCH 153/851] Fix typos in launch files (#231) * Fix typos in launch files Signed-off-by: Kenji Miyake * Fix lint Signed-off-by: wep21 Co-authored-by: wep21 --- localization_launch/launch/util/util.launch.py | 10 ++++------ .../behavior_planning/behavior_planning.launch.py | 2 +- 2 files changed, 5 insertions(+), 7 deletions(-) diff --git a/localization_launch/launch/util/util.launch.py b/localization_launch/launch/util/util.launch.py index 732102e20a..7555d0c714 100644 --- a/localization_launch/launch/util/util.launch.py +++ b/localization_launch/launch/util/util.launch.py @@ -13,12 +13,10 @@ # limitations under the License. import launch -from launch.actions import DeclareLaunchArgument, OpaqueFunction -from launch.conditions import IfCondition, UnlessCondition, LaunchConfigurationNotEquals +from launch.conditions import LaunchConfigurationNotEquals from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode -from launch.substitutions import EnvironmentVariable def generate_launch_description(): @@ -29,7 +27,7 @@ def generate_launch_description(): remappings=[ ('input', LaunchConfiguration('input_sensor_points_topic')), ('output', - 'mesurement_range/pointcloud'), + 'measurement_range/pointcloud'), ], parameters=[{ 'input_frame': LaunchConfiguration('base_frame'), @@ -52,7 +50,7 @@ def generate_launch_description(): name='voxel_grid_downsample_filter', remappings=[ ('input', - 'mesurement_range/pointcloud'), + 'measurement_range/pointcloud'), ('output', LaunchConfiguration('output_voxel_grid_downsample_sensor_points_topic')), ], diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 23a9866f70..4118f79f5a 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -56,7 +56,7 @@ def generate_launch_description(): ('~/output/lane_change_path', 'path_with_lane_id'), ('~/output/lane_change_ready', '/planning/scenario_planning/lane_driving/lane_change_ready'), - ('~/output/lane_change_avialable', + ('~/output/lane_change_available', '/planning/scenario_planning/lane_driving/lane_change_available'), ('~/output/stop_reasons', '/planning/scenario_planning/status/stop_reasons'), ('~/debug/lane_change_candidate_path', From 38b6aba6f6afa16c799a07c1dfd0588561dd6757 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 25 May 2021 01:24:11 +0900 Subject: [PATCH 154/851] Format launch files (#228) * Format launch files Signed-off-by: Kenji Miyake * Format launch.py Signed-off-by: Kenji Miyake * Fix lint Signed-off-by: Kenji Miyake --- control_launch/launch/control.launch.py | 30 +++++++++++-------- integration_launch/launch/release.launch.xml | 2 +- .../launch/util/util.launch.xml | 2 +- map_launch/launch/map.launch.py | 11 ++++--- .../traffic_light_node_container.launch.py | 4 +-- .../mission_planning.launch.py | 3 +- .../behavior_planning.launch.py | 22 +++++++------- .../motion_planning/motion_planning.launch.py | 14 +++++---- .../scenario_planning/parking.launch.py | 15 ++++++---- .../pointcloud_preprocessor.launch.py | 23 ++++++++------ .../aip_s1/pointcloud_preprocessor.launch.py | 24 ++++++++------- .../aip_x1/pointcloud_preprocessor.launch.py | 12 +++++--- .../aip_x2/pointcloud_preprocessor.launch.py | 25 +++++++++------- .../aip_xx1/pointcloud_preprocessor.launch.py | 23 ++++++++------ .../aip_xx2/pointcloud_preprocessor.launch.py | 27 ++++++++++------- sensing_launch/launch/livox_horizon.launch.py | 14 +++++---- .../launch/velodyne_node_container.launch.py | 15 ++++++---- 17 files changed, 158 insertions(+), 108 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 8df28d4e8b..36dace32a1 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -13,15 +13,19 @@ # limitations under the License. import launch -from launch.actions import DeclareLaunchArgument, GroupAction,\ - OpaqueFunction, SetLaunchConfiguration -from launch.conditions import IfCondition, LaunchConfigurationEquals, UnlessCondition +from launch.actions import DeclareLaunchArgument +from launch.actions import GroupAction +from launch.actions import OpaqueFunction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import LaunchConfigurationEquals +from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration - -from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes, PushRosNamespace +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes +from launch_ros.actions import PushRosNamespace from launch_ros.descriptions import ComposableNode from launch_ros.substitutions import FindPackageShare - import yaml @@ -388,10 +392,12 @@ def add_launch_arg(name: str, default_value=None): condition=IfCondition(LaunchConfiguration('use_multithread')) ) return launch.LaunchDescription( - launch_arguments + - [set_container_executable, - set_container_mt_executable] + - [ - OpaqueFunction(function=launch_setup) - ] + launch_arguments + + [ + set_container_executable, + set_container_mt_executable, + ] + + [ + OpaqueFunction(function=launch_setup) + ] ) diff --git a/integration_launch/launch/release.launch.xml b/integration_launch/launch/release.launch.xml index 299651f515..d436a4806e 100644 --- a/integration_launch/launch/release.launch.xml +++ b/integration_launch/launch/release.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 f9dda33dec..f1727a7c1a 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -21,6 +21,6 @@ - + diff --git a/map_launch/launch/map.launch.py b/map_launch/launch/map.launch.py index 1d0712b32c..c72c85b251 100644 --- a/map_launch/launch/map.launch.py +++ b/map_launch/launch/map.launch.py @@ -13,11 +13,14 @@ # limitations under the License. import launch -from launch.actions import DeclareLaunchArgument, GroupAction, SetLaunchConfiguration -from launch.conditions import IfCondition, UnlessCondition +from launch.actions import DeclareLaunchArgument +from launch.actions import GroupAction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration - -from launch_ros.actions import ComposableNodeContainer, PushRosNamespace +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import PushRosNamespace from launch_ros.descriptions import ComposableNode 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 054b122d7f..8b08ad4068 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 @@ -15,12 +15,12 @@ import os 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.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode diff --git a/planning_launch/launch/mission_planning/mission_planning.launch.py b/planning_launch/launch/mission_planning/mission_planning.launch.py index cef5f74c69..2e5cf63e27 100644 --- a/planning_launch/launch/mission_planning/mission_planning.launch.py +++ b/planning_launch/launch/mission_planning/mission_planning.launch.py @@ -11,6 +11,7 @@ # 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 @@ -63,6 +64,6 @@ def generate_launch_description(): ], ) return launch.LaunchDescription([ - DeclareLaunchArgument("use_intra_process", default_value='false'), + DeclareLaunchArgument('use_intra_process', default_value='false'), container ]) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 4118f79f5a..70f8e977d5 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -12,16 +12,18 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os + from ament_index_python.packages import get_package_share_directory import launch -from launch.actions import DeclareLaunchArgument, SetLaunchConfiguration, ExecuteProcess -from launch.conditions import IfCondition, UnlessCondition +from launch.actions import DeclareLaunchArgument +from launch.actions import ExecuteProcess +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration - from launch_ros.actions import ComposableNodeContainer from launch_ros.descriptions import ComposableNode - -import os import yaml @@ -65,11 +67,11 @@ def generate_launch_description(): parameters=[ lane_change_planner_param, { - "enable_abort_lane_change": False, - "enable_collision_check_at_prepare_phase": False, - "use_predicted_path_outside_lanelet": False, - "use_all_predicted_path": False, - "enable_blocked_by_obstacle": False, + 'enable_abort_lane_change': False, + 'enable_collision_check_at_prepare_phase': False, + 'use_predicted_path_outside_lanelet': False, + 'use_all_predicted_path': False, + 'enable_blocked_by_obstacle': False, } ], extra_arguments=[ diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index b5caf17fe2..5abfdbfc62 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -12,16 +12,18 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os + from ament_index_python.packages import get_package_share_directory import launch -from launch.actions import DeclareLaunchArgument, SetLaunchConfiguration -from launch.conditions import IfCondition, UnlessCondition +from launch.actions import DeclareLaunchArgument +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration - -from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode - -import os import yaml diff --git a/planning_launch/launch/scenario_planning/parking.launch.py b/planning_launch/launch/scenario_planning/parking.launch.py index 4a83f7a0bb..d831a3bcd4 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.py +++ b/planning_launch/launch/scenario_planning/parking.launch.py @@ -11,11 +11,16 @@ # 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, GroupAction, SetLaunchConfiguration -from launch.conditions import IfCondition, UnlessCondition +from launch.actions import DeclareLaunchArgument +from launch.actions import GroupAction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer, PushRosNamespace +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import PushRosNamespace from launch_ros.descriptions import ComposableNode @@ -123,8 +128,8 @@ def generate_launch_description(): ) return launch.LaunchDescription([ - DeclareLaunchArgument("use_intra_process", default_value='false'), - DeclareLaunchArgument("use_multithread", default_value='false'), + DeclareLaunchArgument('use_intra_process', default_value='false'), + DeclareLaunchArgument('use_multithread', default_value='false'), set_container_executable, set_container_mt_executable, GroupAction([ diff --git a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py index bf1dcba906..a9e3b03e55 100644 --- a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py @@ -13,16 +13,19 @@ # 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, OpaqueFunction, SetLaunchConfiguration -from launch.conditions import IfCondition, UnlessCondition +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode -from launch.substitutions import EnvironmentVariable +import yaml + def get_vehicle_info(context): path = LaunchConfiguration('vehicle_param_file').perform(context) @@ -38,6 +41,7 @@ def get_vehicle_info(context): 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: @@ -120,9 +124,9 @@ def launch_setup(context, *args, **kwargs): ('output', 'no_ground/pointcloud') ], parameters=[{ - "general_max_slope": 10.0, - "local_max_slope": 10.0, - "min_height_threshold": 0.2, + 'general_max_slope': 10.0, + 'local_max_slope': 10.0, + 'min_height_threshold': 0.2, }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -157,6 +161,7 @@ def launch_setup(context, *args, **kwargs): return [container, concat_loader, passthrough_loader] + def generate_launch_description(): launch_arguments = [] diff --git a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py index 9e1c1cd45a..438fee810b 100644 --- a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py @@ -12,16 +12,18 @@ # 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, OpaqueFunction, SetLaunchConfiguration -from launch.conditions import IfCondition, UnlessCondition +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode -from launch.substitutions import EnvironmentVariable +import yaml + def get_vehicle_info(context): path = LaunchConfiguration('vehicle_param_file').perform(context) @@ -37,6 +39,7 @@ def get_vehicle_info(context): 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: @@ -119,9 +122,9 @@ def launch_setup(context, *args, **kwargs): ('output', 'no_ground/pointcloud') ], parameters=[{ - "general_max_slope": 10.0, - "local_max_slope": 10.0, - "min_height_threshold": 0.2, + 'general_max_slope': 10.0, + 'local_max_slope': 10.0, + 'min_height_threshold': 0.2, }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -156,6 +159,7 @@ def launch_setup(context, *args, **kwargs): return [container, concat_loader, passthrough_loader] + def generate_launch_description(): launch_arguments = [] diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py index 4c8232cbc5..e577f912ae 100644 --- a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py @@ -14,10 +14,14 @@ # limitations under the License. import launch -from launch.actions import DeclareLaunchArgument, OpaqueFunction, SetLaunchConfiguration -from launch.conditions import IfCondition, UnlessCondition -from launch.substitutions import EnvironmentVariable, LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode import yaml diff --git a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py index 8e0e597abd..2da76720bf 100644 --- a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py @@ -13,16 +13,18 @@ # 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, OpaqueFunction, SetLaunchConfiguration -from launch.conditions import IfCondition, UnlessCondition +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer from launch_ros.descriptions import ComposableNode -from launch.substitutions import EnvironmentVariable +import yaml + def get_vehicle_info(context): path = LaunchConfiguration('vehicle_param_file').perform(context) @@ -38,6 +40,7 @@ def get_vehicle_info(context): 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: @@ -45,7 +48,6 @@ def get_vehicle_mirror_info(context): return p - def launch_setup(context, *args, **kwargs): pkg = 'pointcloud_preprocessor' @@ -61,8 +63,8 @@ def launch_setup(context, *args, **kwargs): 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/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], 'output_frame': 'base_link', }], extra_arguments=[{ @@ -123,9 +125,9 @@ def launch_setup(context, *args, **kwargs): ('/output', 'no_ground/pointcloud') ], parameters=[{ - "general_max_slope": 10.0, - "local_max_slope": 10.0, - "min_height_threshold": 0.2, + 'general_max_slope': 10.0, + 'local_max_slope': 10.0, + 'min_height_threshold': 0.2, }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -148,6 +150,7 @@ def launch_setup(context, *args, **kwargs): return [container] + def generate_launch_description(): launch_arguments = [] diff --git a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py index bf1dcba906..a9e3b03e55 100644 --- a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py @@ -13,16 +13,19 @@ # 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, OpaqueFunction, SetLaunchConfiguration -from launch.conditions import IfCondition, UnlessCondition +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode -from launch.substitutions import EnvironmentVariable +import yaml + def get_vehicle_info(context): path = LaunchConfiguration('vehicle_param_file').perform(context) @@ -38,6 +41,7 @@ def get_vehicle_info(context): 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: @@ -120,9 +124,9 @@ def launch_setup(context, *args, **kwargs): ('output', 'no_ground/pointcloud') ], parameters=[{ - "general_max_slope": 10.0, - "local_max_slope": 10.0, - "min_height_threshold": 0.2, + 'general_max_slope': 10.0, + 'local_max_slope': 10.0, + 'min_height_threshold': 0.2, }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -157,6 +161,7 @@ def launch_setup(context, *args, **kwargs): return [container, concat_loader, passthrough_loader] + def generate_launch_description(): launch_arguments = [] diff --git a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py index 95af0e098b..0485ff3378 100644 --- a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py @@ -13,16 +13,19 @@ # 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, OpaqueFunction, SetLaunchConfiguration -from launch.conditions import IfCondition, UnlessCondition +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode -from launch.substitutions import EnvironmentVariable +import yaml + def get_vehicle_info(context): path = LaunchConfiguration('vehicle_param_file').perform(context) @@ -38,6 +41,7 @@ def get_vehicle_info(context): 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: @@ -59,8 +63,8 @@ def launch_setup(context, *args, **kwargs): 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/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], 'output_frame': 'base_link', }], extra_arguments=[{ @@ -120,9 +124,9 @@ def launch_setup(context, *args, **kwargs): ('output', 'no_ground/pointcloud') ], parameters=[{ - "general_max_slope": 10.0, - "local_max_slope": 10.0, - "min_height_threshold": 0.2, + 'general_max_slope': 10.0, + 'local_max_slope': 10.0, + 'min_height_threshold': 0.2, }], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -157,6 +161,7 @@ def launch_setup(context, *args, **kwargs): return [container, concat_loader, passthrough_loader] + def generate_launch_description(): launch_arguments = [] diff --git a/sensing_launch/launch/livox_horizon.launch.py b/sensing_launch/launch/livox_horizon.launch.py index 93907c22d4..af5a5560ee 100644 --- a/sensing_launch/launch/livox_horizon.launch.py +++ b/sensing_launch/launch/livox_horizon.launch.py @@ -13,15 +13,17 @@ # See the License for the specific language governing permissions and # limitations under the License. -import launch -import yaml import os + from ament_index_python.packages import get_package_share_directory -from launch.actions import DeclareLaunchArgument, OpaqueFunction +import launch +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode -from launch.substitutions import EnvironmentVariable +import yaml def get_vehicle_info(context): @@ -157,7 +159,7 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg('output_type', '0') add_launch_arg('lvx_file_path', 'livox_test.lvx') add_launch_arg('user_config_path', os.path.join(get_package_share_directory( - "livox_ros2_driver"), "config/livox_lidar_config.json")) + 'livox_ros2_driver'), 'config/livox_lidar_config.json')) add_launch_arg('bd_code_param_path') add_launch_arg('launch_driver') add_launch_arg('base_frame', 'base_link') diff --git a/sensing_launch/launch/velodyne_node_container.launch.py b/sensing_launch/launch/velodyne_node_container.launch.py index 972a5716a4..7f4a3ec7b2 100644 --- a/sensing_launch/launch/velodyne_node_container.launch.py +++ b/sensing_launch/launch/velodyne_node_container.launch.py @@ -13,12 +13,15 @@ # limitations under the License. import launch -from launch.actions import DeclareLaunchArgument, OpaqueFunction, SetLaunchConfiguration -from launch.conditions import IfCondition, UnlessCondition -from launch.substitutions import EnvironmentVariable, LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode - import yaml @@ -64,7 +67,7 @@ def create_parameter_dict(*args): 'num_points_thresholds', 'invalid_intensity', 'frame_id', 'scan_phase'), - }], + }], remappings=[('velodyne_points', 'pointcloud_raw'), ('velodyne_points_ex', 'pointcloud_raw_ex')], extra_arguments=[{ From c70e42fdc578bddf9f72dba1999a0408341ed9de Mon Sep 17 00:00:00 2001 From: Tatsuya Yamasaki Date: Tue, 25 May 2021 19:29:50 +0900 Subject: [PATCH 155/851] Exclude dummy_perception_publisher.launch.xml if is scenario_simulation (#230) --- .../launch/planning_simulator.launch.xml | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 3abbf6bf4f..3e13089057 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -48,12 +48,13 @@ - - - - - - + + + + + + + From 38d3357028439fe1b11c65959a152516615aee01 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 31 May 2021 09:54:56 +0900 Subject: [PATCH 156/851] Fix GPG problem (#234) Signed-off-by: Kenji Miyake --- .github/workflows/build_and_test.yml | 8 ++++++++ .github/workflows/build_and_test_pr.yml | 8 ++++++++ 2 files changed, 16 insertions(+) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 369290930d..2a881bb28d 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -18,6 +18,14 @@ jobs: - name: Checkout repository uses: actions/checkout@v2 + # https://github.com/osrf/docker_images/issues/535 + - name: Temporarily fix GPG problem + run: | + sudo rm /etc/apt/sources.list.d/ros2-latest.list + sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg + echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null + sudo apt-get -y update + - name: Install pip run: | apt-get -y update diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml index cede36fb75..af07b954eb 100644 --- a/.github/workflows/build_and_test_pr.yml +++ b/.github/workflows/build_and_test_pr.yml @@ -25,6 +25,14 @@ jobs: # Fetch with depth=0 to calculate modified packages fetch-depth: 0 + # https://github.com/osrf/docker_images/issues/535 + - name: Temporarily fix GPG problem + run: | + sudo rm /etc/apt/sources.list.d/ros2-latest.list + sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg + echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null + sudo apt-get -y update + - name: Install pip run: | apt-get -y update From 5658d66d431d8bc0d703279c78f23f7123e10d65 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Mon, 31 May 2021 12:05:26 +0900 Subject: [PATCH 157/851] Add description to PULL_REQUEST_TEMPLATE (#235) --- .github/PULL_REQUEST_TEMPLATE.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md index 60b1122dae..95347e58f0 100644 --- a/.github/PULL_REQUEST_TEMPLATE.md +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -24,11 +24,15 @@ ## Pre-Review Checklist for the PR Author +**PR Author should check the checkboxes below when creating the PR.** + - [ ] Code follows [coding guidelines][coding-guidelines] - [ ] Assign PR to reviewer ## Checklist for the PR Reviewer +**Reviewers should check the checkboxes below before approval.** + - [ ] Commits are properly organized and messages are according to the guideline - [ ] Code follows [coding guidelines][coding-guidelines] - [ ] (Optional) Unit tests have been written for new behavior @@ -36,6 +40,8 @@ ## Post-Review Checklist for the PR Author +**PR Author should check the checkboxes below before merging.** + - [ ] All open points are addressed and tracked via issues or tickets - [ ] Write [release notes][release-notes] From dc036e55f6d4396afbca3096b70644c2577156a5 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Mon, 31 May 2021 19:52:01 +0900 Subject: [PATCH 158/851] add external commands (#210) * add remote commands * fix topic * ToExternalCmd * fix topic in remote cmd converter * fix ament --- control_launch/launch/control.launch.py | 11 ++++++----- control_launch/launch/control.launch.xml | 12 ++++++------ 2 files changed, 12 insertions(+), 11 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 36dace32a1..7afe3ce2bc 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -216,14 +216,15 @@ def launch_setup(context, *args, **kwargs): plugin='ExternalCmdSelector', name='external_cmd_selector', remappings=[ - ('~/input/local/raw_control_cmd', '/external/local/raw_control_cmd'), + ('~/input/local/control_cmd', '/external/local/control_cmd'), ('~/input/local/shift_cmd', '/external/local/shift_cmd'), ('~/input/local/turn_signal_cmd', '/external/local/turn_signal_cmd'), - ('~/input/remote/raw_control_cmd', '/external/remote/raw_control_cmd'), + ('~/input/remote/control_cmd', '/external/remote/control_cmd'), ('~/input/remote/shift_cmd', '/external/remote/shift_cmd'), ('~/input/remote/turn_signal_cmd', '/external/remote/turn_signal_cmd'), ('~/output/current_selector_mode', '~/current_selector_mode'), - ('~/output/raw_control_cmd', '/external/external_cmd_selector/raw_control_cmd'), + ('~/output/external_control_cmd', + '/external/external_cmd_selector/external_control_cmd'), ('~/output/shift_cmd', '/external/external_cmd_selector/shift_cmd'), ('~/output/turn_signal_cmd', '/external/external_cmd_selector/turn_signal_cmd'), ('~/service/select_external_command', '~/select_external_command'), @@ -244,13 +245,13 @@ def launch_setup(context, *args, **kwargs): plugin='RemoteCmdConverter', name='remote_cmd_converter', remappings=[ - ('in/raw_control_cmd', '/external/external_cmd_selector/raw_control_cmd'), + ('in/external_control_cmd', '/external/external_cmd_selector/external_control_cmd'), ('in/shift_cmd', '/external/external_cmd_selector/shift_cmd'), ('in/emergency_stop', '/remote/emergency_stop'), ('in/current_gate_mode', '/control/current_gate_mode'), ('in/twist', '/localization/twist'), ('out/control_cmd', '/external/external_cmd_selector/control_cmd'), - ('out/latest_raw_control_cmd', '/remote/latest_raw_control_cmd'), + ('out/latest_remote_control_cmd', '/remote/latest_remote_control_cmd'), ], parameters=[ { diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index faeae393a5..940fc887a4 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -60,9 +60,9 @@ - - - + + + @@ -81,18 +81,18 @@ - + - + - + From 6df2eb9bebc7633b10dc0b748bd55f382f22c323 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 3 Jun 2021 14:23:56 +0900 Subject: [PATCH 159/851] Fix topic name of external traffic light input (#236) --- .../lane_driving/behavior_planning/behavior_planning.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 70f8e977d5..f35986b09f 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -162,7 +162,7 @@ def generate_launch_description(): ('~/input/traffic_light_states', '/perception/traffic_light_recognition/traffic_light_states'), ('~/input/external_traffic_light_states', - '/foa/traffic_light_recognition/traffic_light_states'), + '/awapi/traffic_light/put/traffic_light_status'), ('~/output/path', 'path'), ('~/output/stop_reasons', '/planning/scenario_planning/status/stop_reasons'), From 0592adac1be67c8d732103d0e91825b0240fc113 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Fri, 4 Jun 2021 21:30:01 +0900 Subject: [PATCH 160/851] Revert "Fix GPG problem (#234)" (#237) This reverts commit 38d3357028439fe1b11c65959a152516615aee01. --- .github/workflows/build_and_test.yml | 8 -------- .github/workflows/build_and_test_pr.yml | 8 -------- 2 files changed, 16 deletions(-) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 2a881bb28d..369290930d 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -18,14 +18,6 @@ jobs: - name: Checkout repository uses: actions/checkout@v2 - # https://github.com/osrf/docker_images/issues/535 - - name: Temporarily fix GPG problem - run: | - sudo rm /etc/apt/sources.list.d/ros2-latest.list - sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg - echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null - sudo apt-get -y update - - name: Install pip run: | apt-get -y update diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml index af07b954eb..cede36fb75 100644 --- a/.github/workflows/build_and_test_pr.yml +++ b/.github/workflows/build_and_test_pr.yml @@ -25,14 +25,6 @@ jobs: # Fetch with depth=0 to calculate modified packages fetch-depth: 0 - # https://github.com/osrf/docker_images/issues/535 - - name: Temporarily fix GPG problem - run: | - sudo rm /etc/apt/sources.list.d/ros2-latest.list - sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg - echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null - sudo apt-get -y update - - name: Install pip run: | apt-get -y update From b5d370d4c3ec274ff9861af70351c17fd16823be Mon Sep 17 00:00:00 2001 From: Kazuki Miyahara Date: Mon, 7 Jun 2021 19:13:38 +0900 Subject: [PATCH 161/851] Add the description for CI checks to the PR template (#240) --- .github/PULL_REQUEST_TEMPLATE.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md index 95347e58f0..e0864cce57 100644 --- a/.github/PULL_REQUEST_TEMPLATE.md +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -45,5 +45,11 @@ - [ ] All open points are addressed and tracked via issues or tickets - [ ] Write [release notes][release-notes] +## CI Checks + +- **Build and test for PR**: Required to pass before the merge. +- **Check spelling**: NOT required to pass before the merge. It is up to the reviewer(s). See [here][spell-check-dict] if you want to add some words to the spell check dictionary. + [coding-guidelines]: https://tier4.atlassian.net/wiki/spaces/AIP/pages/1194394777/T4 [release-notes]: https://tier4.atlassian.net/wiki/spaces/AIP/pages/563774416 +[spell-check-dict]: https://github.com/tier4/autoware-spell-check-dict#how-to-contribute From 7f824f564cf6e71993aab89d0db69d91529b6a47 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 9 Jun 2021 18:29:57 +0900 Subject: [PATCH 162/851] Put image decompressor into container (#241) * Put image decompressor into container Signed-off-by: wep21 * Fix bug Signed-off-by: wep21 --- .../traffic_light.launch.xml | 10 +--- .../traffic_light_node_container.launch.py | 55 +++++++++++++++++-- perception_launch/package.xml | 3 +- 3 files changed, 53 insertions(+), 15 deletions(-) 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 29ad7c1a43..64335205da 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -1,18 +1,10 @@ - - - - - - - - @@ -30,5 +22,7 @@ + + 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 8b08ad4068..8204a86a8f 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 @@ -18,6 +18,9 @@ import launch from launch import LaunchDescription from launch.actions import DeclareLaunchArgument +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer from launch_ros.actions import LoadComposableNodes @@ -65,6 +68,9 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg('input_h', '224') add_launch_arg('input_w', '224') + add_launch_arg('use_intra_process', 'False') + add_launch_arg('use_multithread', 'False') + def create_parameter_dict(*args): result = {} for x in args: @@ -75,8 +81,20 @@ def create_parameter_dict(*args): name='traffic_light_node_container', namespace='/perception/traffic_light_recognition', package='rclcpp_components', - executable='component_container', + executable=LaunchConfiguration('container_executable'), composable_node_descriptions=[ + ComposableNode( + package='image_transport_decompressor', + plugin='image_preprocessor::ImageTransportDecompressor', + name='traffic_light_image_decompressor', + parameters=[{'encoding': 'rgb8'}], + remappings=[('~/input/compressed_image', + [LaunchConfiguration('input/image'), '/compressed']), + ('~/output/raw_image', LaunchConfiguration('input/image'))], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], + ), ComposableNode( package='traffic_light_classifier', plugin='traffic_light::TrafficLightClassifierNodelet', @@ -86,7 +104,10 @@ def create_parameter_dict(*args): 'precision', 'input_c', 'input_h', 'input_w')], remappings=[('~/input/image', LaunchConfiguration('input/image')), ('~/input/rois', 'rois'), - ('~/output/traffic_light_states', 'traffic_light_states')] + ('~/output/traffic_light_states', 'traffic_light_states')], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ), ComposableNode( package='traffic_light_visualization', @@ -100,7 +121,10 @@ def create_parameter_dict(*args): ('~/output/image', 'debug/rois'), ('~/output/image/compressed', 'debug/rois/compressed'), ('~/output/image/compressedDepth', 'debug/rois/compressedDepth'), - ('~/output/image/theora', 'debug/rois/theora')] + ('~/output/image/theora', 'debug/rois/theora')], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ) ], output='both', @@ -120,11 +144,32 @@ def create_parameter_dict(*args): parameters=[ssd_fine_detector_param], remappings=[('~/input/image', LaunchConfiguration('input/image')), ('~/input/rois', 'rough/rois'), - ('~/output/rois', 'rois')] + ('~/output/rois', 'rois')], + extra_arguments=[{ + 'use_intra_process_comms': LaunchConfiguration('use_intra_process') + }], ), ], target_container=container, condition=launch.conditions.IfCondition(LaunchConfiguration('enable_fine_detection')), ) - return LaunchDescription(launch_arguments + [container, loader]) + set_container_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container', + condition=UnlessCondition(LaunchConfiguration('use_multithread')) + ) + + set_container_mt_executable = SetLaunchConfiguration( + 'container_executable', + 'component_container_mt', + condition=IfCondition(LaunchConfiguration('use_multithread')) + ) + + return LaunchDescription([ + *launch_arguments, + set_container_executable, + set_container_mt_executable, + container, + loader, + ]) diff --git a/perception_launch/package.xml b/perception_launch/package.xml index 4260e43493..38fe7e3761 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -24,8 +24,7 @@ object_merger - image_transport - image_transport_plugins + image_transport_decompressor traffic_light_map_based_detector traffic_light_ssd_fine_detector traffic_light_classifier From 279acbd4693e690e250e9bd1ea64659d95648e7b Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 9 Jun 2021 19:14:59 +0900 Subject: [PATCH 163/851] Fix aip_xx1 camera launch (#242) Signed-off-by: wep21 --- sensing_launch/launch/aip_xx1/camera.launch.xml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/sensing_launch/launch/aip_xx1/camera.launch.xml b/sensing_launch/launch/aip_xx1/camera.launch.xml index 14d7a080bc..09cfea332e 100644 --- a/sensing_launch/launch/aip_xx1/camera.launch.xml +++ b/sensing_launch/launch/aip_xx1/camera.launch.xml @@ -13,12 +13,14 @@ + - + + From 78864d5b62a57e1986765bc20c4fe542bf94ba6f Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 10 Jun 2021 14:03:57 +0900 Subject: [PATCH 164/851] Fix gnss topic name (#243) Signed-off-by: wep21 --- sensing_launch/launch/aip_customized/gnss.launch.xml | 2 +- sensing_launch/launch/aip_s1/gnss.launch.xml | 2 +- sensing_launch/launch/aip_x1/gnss.launch.xml | 2 +- sensing_launch/launch/aip_x2/gnss.launch.xml | 2 +- sensing_launch/launch/aip_xx1/gnss.launch.xml | 2 +- sensing_launch/launch/aip_xx2/gnss.launch.xml | 2 +- 6 files changed, 6 insertions(+), 6 deletions(-) diff --git a/sensing_launch/launch/aip_customized/gnss.launch.xml b/sensing_launch/launch/aip_customized/gnss.launch.xml index 7273ddee1b..72c636b291 100644 --- a/sensing_launch/launch/aip_customized/gnss.launch.xml +++ b/sensing_launch/launch/aip_customized/gnss.launch.xml @@ -8,7 +8,7 @@ - + diff --git a/sensing_launch/launch/aip_s1/gnss.launch.xml b/sensing_launch/launch/aip_s1/gnss.launch.xml index 7273ddee1b..72c636b291 100644 --- a/sensing_launch/launch/aip_s1/gnss.launch.xml +++ b/sensing_launch/launch/aip_s1/gnss.launch.xml @@ -8,7 +8,7 @@ - + diff --git a/sensing_launch/launch/aip_x1/gnss.launch.xml b/sensing_launch/launch/aip_x1/gnss.launch.xml index 113f7be35d..2db11f1608 100644 --- a/sensing_launch/launch/aip_x1/gnss.launch.xml +++ b/sensing_launch/launch/aip_x1/gnss.launch.xml @@ -9,7 +9,7 @@ - + diff --git a/sensing_launch/launch/aip_x2/gnss.launch.xml b/sensing_launch/launch/aip_x2/gnss.launch.xml index 7273ddee1b..72c636b291 100644 --- a/sensing_launch/launch/aip_x2/gnss.launch.xml +++ b/sensing_launch/launch/aip_x2/gnss.launch.xml @@ -8,7 +8,7 @@ - + diff --git a/sensing_launch/launch/aip_xx1/gnss.launch.xml b/sensing_launch/launch/aip_xx1/gnss.launch.xml index 2c0be5a34b..f8d7331f3e 100644 --- a/sensing_launch/launch/aip_xx1/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx1/gnss.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 7273ddee1b..72c636b291 100644 --- a/sensing_launch/launch/aip_xx2/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx2/gnss.launch.xml @@ -8,7 +8,7 @@ - + From f753a1e358513a67bc8ff4a9c8e5001ccb0df573 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 22 Jun 2021 16:50:57 +0900 Subject: [PATCH 165/851] Replace insteadof with insteadOf (#245) Signed-off-by: Kenji Miyake --- .github/workflows/build_and_test.yml | 2 +- .github/workflows/build_and_test_pr.yml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 369290930d..3426aa01f5 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -57,7 +57,7 @@ jobs: - name: Set git config for private repositories run: | git config --local --unset-all http.https://github.com/.extraheader || true - git config --global url.https://${{ secrets.REPO_TOKEN }}@github.com.insteadof 'https://github.com' + git config --global url.https://${{ secrets.REPO_TOKEN }}@github.com.insteadOf 'https://github.com' - name: Clone dependency packages run: | diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml index cede36fb75..caf38d3dd5 100644 --- a/.github/workflows/build_and_test_pr.yml +++ b/.github/workflows/build_and_test_pr.yml @@ -67,7 +67,7 @@ jobs: if: ${{ steps.list_packages.outputs.package_list != '' }} run: | git config --local --unset-all http.https://github.com/.extraheader || true - git config --global url.https://${{ secrets.REPO_TOKEN }}@github.com.insteadof 'https://github.com' + git config --global url.https://${{ secrets.REPO_TOKEN }}@github.com.insteadOf 'https://github.com' - name: Clone dependency packages if: ${{ steps.list_packages.outputs.package_list != '' }} From 98ce820449d04da7465ab86ea4feace5e3bfb294 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 29 Jun 2021 19:48:08 +0900 Subject: [PATCH 166/851] Add namespace to behavior_velocity_planner (#252) Signed-off-by: Kenji Miyake --- .../lane_driving/behavior_planning/behavior_planning.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index f35986b09f..677230e71f 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -150,7 +150,7 @@ def generate_launch_description(): behavior_velocity_planner_component = ComposableNode( package='behavior_velocity_planner', - plugin='BehaviorVelocityPlannerNode', + plugin='behavior_velocity_planner::BehaviorVelocityPlannerNode', name='behavior_velocity_planner', namespace='', remappings=[ From 490e9e9ebb5e4171d2f978af114f1a9f85c91598 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 29 Jun 2021 20:37:27 +0900 Subject: [PATCH 167/851] Remove exec depend in CI (#250) * Fix bug Signed-off-by: Kenji Miyake * Remove exec_depend to avoid unnecessary build Signed-off-by: Kenji Miyake --- .github/workflows/build_and_test.yml | 8 ++++++-- .github/workflows/build_and_test_pr.yml | 9 +++++++-- 2 files changed, 13 insertions(+), 4 deletions(-) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 3426aa01f5..41a58dc142 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -40,6 +40,10 @@ jobs: run: | echo "Target packages: ${{ steps.list_packages.outputs.package_list }}" + - name: Remove exec_depend to avoid unnecessary build + run: | + find . -name package.xml | xargs -I {} sed -i -rz "s|\s*[a-zA-Z_0-9]+\s*\n||g" {} + - name: Install yq run: | apt-get -y update @@ -50,9 +54,9 @@ jobs: - name: Create build_depends.repos run: | curl -sSL -H "Authorization: token ${{ secrets.REPO_TOKEN }}" ${{ env.BUILD_DEPEND_FILE }} | sed -e "s|git@github.com:|https://github.com/|g" > build_depends.repos - repo_key=$(grep ${{ env.SELF_REPO }} build_depends.repos -B2 | grep ":\$" | sed -r 's|\s+([a-zA-Z/]+):|\1|g') + repo_key=$(grep ${{ env.SELF_REPO }} build_depends.repos -B2 | grep ":\$" | sed -r 's|\s+([a-zA-Z/\.]+):|\1|g') echo "Remove $repo_key from build_depends.repos" - yq eval --inplace "del(.repositories.${repo_key})" build_depends.repos + yq eval --inplace "del(.repositories.\"${repo_key}\")" build_depends.repos - name: Set git config for private repositories run: | diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml index caf38d3dd5..86b0dac6d1 100644 --- a/.github/workflows/build_and_test_pr.yml +++ b/.github/workflows/build_and_test_pr.yml @@ -47,6 +47,11 @@ jobs: run: | echo "Target packages: ${{ steps.list_packages.outputs.package_list }}" + - name: Remove exec_depend to avoid unnecessary build + if: ${{ steps.list_packages.outputs.package_list != '' }} + run: | + find . -name package.xml | xargs -I {} sed -i -rz "s|\s*[a-zA-Z_0-9]+\s*\n||g" {} + - name: Install yq if: ${{ steps.list_packages.outputs.package_list != '' }} run: | @@ -59,9 +64,9 @@ jobs: if: ${{ steps.list_packages.outputs.package_list != '' }} run: | curl -sSL -H "Authorization: token ${{ secrets.REPO_TOKEN }}" ${{ env.BUILD_DEPEND_FILE }} | sed -e "s|git@github.com:|https://github.com/|g" > build_depends.repos - repo_key=$(grep ${{ env.SELF_REPO }} build_depends.repos -B2 | grep ":\$" | sed -r 's|\s+([a-zA-Z/]+):|\1|g') + repo_key=$(grep ${{ env.SELF_REPO }} build_depends.repos -B2 | grep ":\$" | sed -r 's|\s+([a-zA-Z/\.]+):|\1|g') echo "Remove $repo_key from build_depends.repos" - yq eval --inplace "del(.repositories.${repo_key})" build_depends.repos + yq eval --inplace "del(.repositories.\"${repo_key}\")" build_depends.repos - name: Set git config for private repositories if: ${{ steps.list_packages.outputs.package_list != '' }} From e9ae09c651d18a1d90efc23072766d14709f50aa Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 29 Jun 2021 21:21:25 +0900 Subject: [PATCH 168/851] Remove clock publisher (#217) Signed-off-by: wep21 --- autoware_launch/launch/autoware.launch.xml | 3 --- 1 file changed, 3 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index b36abfc84c..01325d8112 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -71,7 +71,4 @@ - - - From 32e564c4070f9f7edbbcd42a90a11b07569a5b38 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 29 Jun 2021 22:06:39 +0900 Subject: [PATCH 169/851] Fixup for #217 (#254) * Fixup for #217 Signed-off-by: Kenji Miyake * Fix typo Signed-off-by: Kenji Miyake --- autoware_launch/launch/planning_simulator.launch.xml | 4 ---- autoware_launch/package.xml | 1 - integration_launch/package.xml | 5 ++--- 3 files changed, 2 insertions(+), 8 deletions(-) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 3e13089057..cc2b7e0734 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -74,8 +74,4 @@ - - - - diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 1432b69685..d486662a5c 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -11,7 +11,6 @@ control_launch - clock_publisher localization_launch map_launch perception_launch diff --git a/integration_launch/package.xml b/integration_launch/package.xml index 2f5e95d847..dc8da62d65 100644 --- a/integration_launch/package.xml +++ b/integration_launch/package.xml @@ -6,11 +6,10 @@ Hiroyuki Obinata Apache 2 -ament_cmake_auto + ament_cmake_auto control_launch - clock_publisher localization_launch map_launch perception_launch @@ -19,7 +18,7 @@ system_launch vehicle_launch - + rviz2 From 852cfad2b6d8f8fc563ba784ca595b7a03389e47 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Thu, 1 Jul 2021 15:15:33 +0900 Subject: [PATCH 170/851] add dependabot (#258) --- .github/dependabot.yml | 7 +++++++ 1 file changed, 7 insertions(+) create mode 100644 .github/dependabot.yml diff --git a/.github/dependabot.yml b/.github/dependabot.yml new file mode 100644 index 0000000000..b940a74a4c --- /dev/null +++ b/.github/dependabot.yml @@ -0,0 +1,7 @@ +version: 2 +updates: + - package-ecosystem: "github-actions" + directory: "/" + schedule: + interval: "daily" + open-pull-requests-limit: 1 From 7cc03b52a3a2e15eafcf0913cef950c073aa17a4 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Thu, 1 Jul 2021 15:28:22 +0900 Subject: [PATCH 171/851] Bump streetsidesoftware/cspell-action from 1.1.1 to 1.2.5 (#259) Bumps [streetsidesoftware/cspell-action](https://github.com/streetsidesoftware/cspell-action) from 1.1.1 to 1.2.5. - [Release notes](https://github.com/streetsidesoftware/cspell-action/releases) - [Changelog](https://github.com/streetsidesoftware/cspell-action/blob/main/CHANGELOG.md) - [Commits](https://github.com/streetsidesoftware/cspell-action/compare/v1.1.1...v1.2.5) --- updated-dependencies: - dependency-name: streetsidesoftware/cspell-action dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/spell_check_pr.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/spell_check_pr.yml b/.github/workflows/spell_check_pr.yml index c6c3c6c3da..84764d49d3 100644 --- a/.github/workflows/spell_check_pr.yml +++ b/.github/workflows/spell_check_pr.yml @@ -18,6 +18,6 @@ jobs: --output .github/workflows/.cspell.json \ https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json - - uses: streetsidesoftware/cspell-action@v1.1.1 + - uses: streetsidesoftware/cspell-action@v1.2.5 with: config: ".github/workflows/.cspell.json" From 5f34ed25bf9d549216715afc3c14d0bec75408b0 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Fri, 2 Jul 2021 16:24:12 +0900 Subject: [PATCH 172/851] Enable intra process and mt (#204) Signed-off-by: wep21 --- localization_launch/launch/util/util.launch.xml | 2 +- sensing_launch/launch/aip_xx1/lidar.launch.xml | 4 ++-- sensing_launch/launch/velodyne_VLP16.launch.xml | 2 +- sensing_launch/launch/velodyne_VLS128.launch.xml | 4 ++-- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index f1727a7c1a..3a7b67fb1d 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -14,7 +14,7 @@ - + diff --git a/sensing_launch/launch/aip_xx1/lidar.launch.xml b/sensing_launch/launch/aip_xx1/lidar.launch.xml index 940ab9fa9c..2300103af5 100644 --- a/sensing_launch/launch/aip_xx1/lidar.launch.xml +++ b/sensing_launch/launch/aip_xx1/lidar.launch.xml @@ -95,8 +95,8 @@ - - + + diff --git a/sensing_launch/launch/velodyne_VLP16.launch.xml b/sensing_launch/launch/velodyne_VLP16.launch.xml index 7259ed855e..9382390ffa 100644 --- a/sensing_launch/launch/velodyne_VLP16.launch.xml +++ b/sensing_launch/launch/velodyne_VLP16.launch.xml @@ -28,7 +28,7 @@ - + diff --git a/sensing_launch/launch/velodyne_VLS128.launch.xml b/sensing_launch/launch/velodyne_VLS128.launch.xml index a5ed5f30b2..79d35df000 100644 --- a/sensing_launch/launch/velodyne_VLS128.launch.xml +++ b/sensing_launch/launch/velodyne_VLS128.launch.xml @@ -28,8 +28,8 @@ - - + + From d7992fea22168cf96729c0297d58b345384c9c9d Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 5 Jul 2021 09:47:20 +0900 Subject: [PATCH 173/851] Fix CI build depends (#261) * Fix CI build depends Signed-off-by: Kenji Miyake * Remove xacro find package Signed-off-by: Kenji Miyake --- .github/workflows/build_and_test.yml | 28 +------------------------ .github/workflows/build_and_test_pr.yml | 24 --------------------- build_depends.repos | 1 + vehicle_launch/CMakeLists.txt | 1 - vehicle_launch/package.xml | 3 +-- 5 files changed, 3 insertions(+), 54 deletions(-) create mode 100644 build_depends.repos diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 41a58dc142..704a803446 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -5,10 +5,6 @@ on: - cron: "0 19 * * *" # run at 4 AM JST workflow_dispatch: -env: - BUILD_DEPEND_FILE: https://raw.githubusercontent.com/tier4/autoware.proj/main/autoware.proj.repos - SELF_REPO: tier4/autoware_launcher - jobs: build-and-test: runs-on: ubuntu-latest @@ -23,15 +19,7 @@ jobs: apt-get -y update apt-get -y install python3-pip - - name: Install kvaser library - run: | - apt-get -y update - apt-get -y install software-properties-common - add-apt-repository ppa:astuff/kvaser-linux - apt-get -y update - apt-get -y install kvaser-canlib-dev kvaser-drivers-dkms - - - name: Search modified package + - name: Search packages in this repository id: list_packages run: | echo ::set-output name=package_list::$(colcon list --names-only) @@ -44,20 +32,6 @@ jobs: run: | find . -name package.xml | xargs -I {} sed -i -rz "s|\s*[a-zA-Z_0-9]+\s*\n||g" {} - - name: Install yq - run: | - apt-get -y update - apt-get -y install wget - wget -O /usr/local/bin/yq https://github.com/mikefarah/yq/releases/download/v4.9.1/yq_linux_amd64 - chmod +x /usr/local/bin/yq - - - name: Create build_depends.repos - run: | - curl -sSL -H "Authorization: token ${{ secrets.REPO_TOKEN }}" ${{ env.BUILD_DEPEND_FILE }} | sed -e "s|git@github.com:|https://github.com/|g" > build_depends.repos - repo_key=$(grep ${{ env.SELF_REPO }} build_depends.repos -B2 | grep ":\$" | sed -r 's|\s+([a-zA-Z/\.]+):|\1|g') - echo "Remove $repo_key from build_depends.repos" - yq eval --inplace "del(.repositories.\"${repo_key}\")" build_depends.repos - - name: Set git config for private repositories run: | git config --local --unset-all http.https://github.com/.extraheader || true diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml index 86b0dac6d1..944042f937 100644 --- a/.github/workflows/build_and_test_pr.yml +++ b/.github/workflows/build_and_test_pr.yml @@ -30,14 +30,6 @@ jobs: apt-get -y update apt-get -y install python3-pip - - name: Install kvaser library - run: | - apt-get -y update - apt-get -y install software-properties-common - add-apt-repository ppa:astuff/kvaser-linux - apt-get -y update - apt-get -y install kvaser-canlib-dev kvaser-drivers-dkms - - name: Search modified package id: list_packages run: | @@ -52,22 +44,6 @@ jobs: run: | find . -name package.xml | xargs -I {} sed -i -rz "s|\s*[a-zA-Z_0-9]+\s*\n||g" {} - - name: Install yq - if: ${{ steps.list_packages.outputs.package_list != '' }} - run: | - apt-get -y update - apt-get -y install wget - wget -O /usr/local/bin/yq https://github.com/mikefarah/yq/releases/download/v4.9.1/yq_linux_amd64 - chmod +x /usr/local/bin/yq - - - name: Create build_depends.repos - if: ${{ steps.list_packages.outputs.package_list != '' }} - run: | - curl -sSL -H "Authorization: token ${{ secrets.REPO_TOKEN }}" ${{ env.BUILD_DEPEND_FILE }} | sed -e "s|git@github.com:|https://github.com/|g" > build_depends.repos - repo_key=$(grep ${{ env.SELF_REPO }} build_depends.repos -B2 | grep ":\$" | sed -r 's|\s+([a-zA-Z/\.]+):|\1|g') - echo "Remove $repo_key from build_depends.repos" - yq eval --inplace "del(.repositories.\"${repo_key}\")" build_depends.repos - - name: Set git config for private repositories if: ${{ steps.list_packages.outputs.package_list != '' }} run: | diff --git a/build_depends.repos b/build_depends.repos new file mode 100644 index 0000000000..56f46b6f79 --- /dev/null +++ b/build_depends.repos @@ -0,0 +1 @@ +repositories: diff --git a/vehicle_launch/CMakeLists.txt b/vehicle_launch/CMakeLists.txt index a119aa504d..f7f9c23733 100644 --- a/vehicle_launch/CMakeLists.txt +++ b/vehicle_launch/CMakeLists.txt @@ -4,7 +4,6 @@ project(vehicle_launch) add_compile_options(-std=c++14) find_package(ament_cmake_auto REQUIRED) -find_package(xacro REQUIRED) ament_auto_find_build_dependencies() diff --git a/vehicle_launch/package.xml b/vehicle_launch/package.xml index 0b76112636..d9d663ace1 100644 --- a/vehicle_launch/package.xml +++ b/vehicle_launch/package.xml @@ -10,14 +10,13 @@ ament_cmake_auto - xacro - camera_description imu_description livox_description velodyne_description robot_state_publisher simple_planning_simulator + xacro ament_lint_auto ament_lint_common From 30125e13c3b076784c913b1d5e4c05eb6dec78b0 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Thu, 8 Jul 2021 12:02:31 +0900 Subject: [PATCH 174/851] Add global_params.launch.py (#260) Signed-off-by: Kenji Miyake --- autoware_launch/launch/autoware.launch.xml | 5 +- .../launch/global_params.launch.py | 52 +++++++++++++++++++ .../launch/logging_simulator.launch.xml | 7 ++- .../launch/planning_simulator.launch.xml | 7 +-- 4 files changed, 59 insertions(+), 12 deletions(-) create mode 100644 autoware_launch/launch/global_params.launch.py diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 01325d8112..8a98cb5ea5 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -10,9 +10,8 @@ - - - + + diff --git a/autoware_launch/launch/global_params.launch.py b/autoware_launch/launch/global_params.launch.py new file mode 100644 index 0000000000..4763e50496 --- /dev/null +++ b/autoware_launch/launch/global_params.launch.py @@ -0,0 +1,52 @@ +# Copyright 2021 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.actions import OpaqueFunction +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import SetParameter +from launch_ros.substitutions import FindPackageShare + + +def launch_setup(context, *args, **kwargs): + # use_sim_time + set_use_sim_time = SetParameter(name='use_sim_time', value=LaunchConfiguration('use_sim_time')) + + # vehicle_info + vehicle_description_pkg = FindPackageShare([ + LaunchConfiguration('vehicle_model'), '_description']).perform(context) + + load_vehicle_info = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [FindPackageShare('vehicle_launch'), '/launch/vehicle_info.launch.py'] + ), + launch_arguments={ + 'config_file': [vehicle_description_pkg, '/config/vehicle_info.param.yaml'] + }.items() + ) + + return [ + set_use_sim_time, + load_vehicle_info, + ] + + +def generate_launch_description(): + return LaunchDescription([ + DeclareLaunchArgument('use_sim_time', default_value='false'), + OpaqueFunction(function=launch_setup), + ]) diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index ca1784889d..456542c623 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -19,12 +19,11 @@ - - - - + + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index cc2b7e0734..d443d49e0f 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -15,15 +15,12 @@ - - - - - + + From b2b4e4389ce5f9e464750b46508a223788aaef7c Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 19 Jul 2021 16:13:20 +0900 Subject: [PATCH 175/851] Load output_measurement_range_sensor_points_topic param (#271) Signed-off-by: kosuke55 --- localization_launch/launch/util/util.launch.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/localization_launch/launch/util/util.launch.py b/localization_launch/launch/util/util.launch.py index 7555d0c714..bde66951be 100644 --- a/localization_launch/launch/util/util.launch.py +++ b/localization_launch/launch/util/util.launch.py @@ -27,7 +27,7 @@ def generate_launch_description(): remappings=[ ('input', LaunchConfiguration('input_sensor_points_topic')), ('output', - 'measurement_range/pointcloud'), + LaunchConfiguration('output_measurement_range_sensor_points_topic')), ], parameters=[{ 'input_frame': LaunchConfiguration('base_frame'), @@ -50,7 +50,7 @@ def generate_launch_description(): name='voxel_grid_downsample_filter', remappings=[ ('input', - 'measurement_range/pointcloud'), + LaunchConfiguration('output_measurement_range_sensor_points_topic')), ('output', LaunchConfiguration('output_voxel_grid_downsample_sensor_points_topic')), ], From 9674c8d7a3c529d8121b61c7db8c39f6058a2a9c Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 20 Jul 2021 11:17:37 +0900 Subject: [PATCH 176/851] Add sync action (#277) Signed-off-by: wep21 --- .github/workflows/sync-main-for-develop.yml | 62 +++++++++++++++++++++ 1 file changed, 62 insertions(+) create mode 100644 .github/workflows/sync-main-for-develop.yml diff --git a/.github/workflows/sync-main-for-develop.yml b/.github/workflows/sync-main-for-develop.yml new file mode 100644 index 0000000000..619e8d4a7f --- /dev/null +++ b/.github/workflows/sync-main-for-develop.yml @@ -0,0 +1,62 @@ +name: sync main for develop + +on: + schedule: + - cron: "0 19 * * 0" # run at 4 AM JST on Sundays + workflow_dispatch: + +env: + BASE_BRANCH: develop + SYNC_TARGET_BRANCH: main + SYNC_BRANCH: sync-main-for-develop + +jobs: + sync-main-for-develop: + runs-on: ubuntu-20.04 + + steps: + - name: Checkout repository + uses: actions/checkout@v2 + with: + ref: ${{ env.BASE_BRANCH }} + fetch-depth: 0 + + - name: Install tools + run: | + sudo apt-get -y update + sudo apt-get -y install curl git + + - name: Set git config for private repositories + run: | + git config --local --unset-all http.https://github.com/.extraheader || true + git config --global url.https://${{ secrets.REPO_TOKEN_WRITE }}@github.com.insteadOf 'https://github.com' + + - name: Merge target branch + run: | + git config --local user.email "noreply@github.com" + git config --local user.name "Github" + git merge --no-ff origin/${{ env.SYNC_TARGET_BRANCH }} + + - name: Create PR + id: create_pr + uses: peter-evans/create-pull-request@v3 + with: + token: ${{ secrets.REPO_TOKEN_WRITE }} + commit-message: sync main for develop + committer: GitHub + author: GitHub + signoff: false + base: ${{ env.BASE_BRANCH }} + branch: ${{ env.SYNC_BRANCH }} + delete-branch: true + title: sync main for develop + body: | + sync main for develop + labels: | + sync-main-for-develop + draft: false + + - name: Check outputs + run: | + echo "Pull Request Number - ${{ steps.create_pr.outputs.pull-request-number }}" + echo "Pull Request URL - ${{ steps.create_pr.outputs.pull-request-url }}" From 80d2769d0cdaf5b78d1c028a7dd169deea9319b2 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 20 Jul 2021 11:53:50 +0900 Subject: [PATCH 177/851] Remove options from CI workflows (#279) Signed-off-by: wep21 --- .github/workflows/build_and_test_pr.yml | 2 -- .github/workflows/spell_check_pr.yml | 2 -- 2 files changed, 4 deletions(-) diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml index 944042f937..f9421aff4e 100644 --- a/.github/workflows/build_and_test_pr.yml +++ b/.github/workflows/build_and_test_pr.yml @@ -2,8 +2,6 @@ name: Build and test for PR on: pull_request: - branches: - - main workflow_dispatch: env: diff --git a/.github/workflows/spell_check_pr.yml b/.github/workflows/spell_check_pr.yml index 84764d49d3..0ace0086f8 100644 --- a/.github/workflows/spell_check_pr.yml +++ b/.github/workflows/spell_check_pr.yml @@ -2,8 +2,6 @@ name: Check spelling on: pull_request: - branches: - - main jobs: spellcheck: From ed38eccebf26545ba58ec993280fd48fde08db59 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 20 Jul 2021 12:30:31 +0900 Subject: [PATCH 178/851] Add labeler action (#278) Signed-off-by: wep21 --- .github/labeler.yml | 4 ++++ .github/workflows/labeler.yml | 12 ++++++++++++ 2 files changed, 16 insertions(+) create mode 100644 .github/labeler.yml create mode 100644 .github/workflows/labeler.yml diff --git a/.github/labeler.yml b/.github/labeler.yml new file mode 100644 index 0000000000..c7f4fae4fc --- /dev/null +++ b/.github/labeler.yml @@ -0,0 +1,4 @@ +ROS2: + - "**" +main: + - "**" diff --git a/.github/workflows/labeler.yml b/.github/workflows/labeler.yml new file mode 100644 index 0000000000..f86110b7b8 --- /dev/null +++ b/.github/workflows/labeler.yml @@ -0,0 +1,12 @@ +name: Labeler ROS2 +on: + pull_request: + +jobs: + triage: + runs-on: ubuntu-latest + + steps: + - uses: actions/labeler@v3 + with: + repo-token: "${{ secrets.GITHUB_TOKEN }}" From 3481dbae43231ccd594b4a60eaa98c5df33b6057 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 20 Jul 2021 19:25:32 +0900 Subject: [PATCH 179/851] add traffic light map viz (#149) (#207) * add traffic light map viz (#149) Signed-off-by: wep21 * Fix launch tag Signed-off-by: wep21 Co-authored-by: Yukihiro Saito Co-authored-by: wep21 --- .../traffic_light_recognition/traffic_light.launch.xml | 5 +++++ 1 file changed, 5 insertions(+) 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 64335205da..eb1f6cf843 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -19,10 +19,15 @@ + + + + + From e79b80dea827139c935c9378dd4d67b69ec5ba34 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 20 Jul 2021 21:58:04 +0900 Subject: [PATCH 180/851] Change sync-main workflow to use GITHUB_TOKEN (#284) Signed-off-by: Kenji Miyake --- .github/workflows/sync-main-for-develop.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/sync-main-for-develop.yml b/.github/workflows/sync-main-for-develop.yml index 619e8d4a7f..d72b576ea2 100644 --- a/.github/workflows/sync-main-for-develop.yml +++ b/.github/workflows/sync-main-for-develop.yml @@ -29,7 +29,7 @@ jobs: - name: Set git config for private repositories run: | git config --local --unset-all http.https://github.com/.extraheader || true - git config --global url.https://${{ secrets.REPO_TOKEN_WRITE }}@github.com.insteadOf 'https://github.com' + git config --global url.https://${{ secrets.GITHUB_TOKEN }}@github.com.insteadOf 'https://github.com' - name: Merge target branch run: | @@ -41,7 +41,7 @@ jobs: id: create_pr uses: peter-evans/create-pull-request@v3 with: - token: ${{ secrets.REPO_TOKEN_WRITE }} + token: ${{ secrets.GITHUB_TOKEN }} commit-message: sync main for develop committer: GitHub author: GitHub From e951899f797a30fe1fac16f41bd9cf4b18b51c76 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 22 Jul 2021 18:09:55 +0900 Subject: [PATCH 181/851] Add time panel (#233) --- autoware_launch/rviz/autoware.rviz | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 8a8d1a535d..4641c2a876 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -18,6 +18,11 @@ Panels: Splitter Ratio: 0.5 - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel Name: InitialPoseButtonPanel + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" Preferences: PromptSaveOnExit: true Toolbars: From f7185ce966cc821473fec3eb94d13d411f846149 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Sat, 24 Jul 2021 10:25:10 +0900 Subject: [PATCH 182/851] Fix sync-main CI to directly create a PR from main branch (#288) Signed-off-by: Kenji Miyake --- .github/workflows/sync-main-for-develop.yml | 34 ++++++++++++--------- 1 file changed, 19 insertions(+), 15 deletions(-) diff --git a/.github/workflows/sync-main-for-develop.yml b/.github/workflows/sync-main-for-develop.yml index d72b576ea2..ea329bf8a5 100644 --- a/.github/workflows/sync-main-for-develop.yml +++ b/.github/workflows/sync-main-for-develop.yml @@ -2,7 +2,7 @@ name: sync main for develop on: schedule: - - cron: "0 19 * * 0" # run at 4 AM JST on Sundays + - cron: "0 19 * * *" # run at 4 AM JST workflow_dispatch: env: @@ -21,27 +21,23 @@ jobs: ref: ${{ env.BASE_BRANCH }} fetch-depth: 0 - - name: Install tools - run: | - sudo apt-get -y update - sudo apt-get -y install curl git - - - name: Set git config for private repositories - run: | - git config --local --unset-all http.https://github.com/.extraheader || true - git config --global url.https://${{ secrets.GITHUB_TOKEN }}@github.com.insteadOf 'https://github.com' + - name: Generate token + uses: tibdex/github-app-token@v1 + id: generate-token + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.APP_PRIVATE_KEY }} - - name: Merge target branch + # To keep the base branch in "create-pull-request", checkout with "BASE_BRANCH" and reset to "SYNC_TARGET_BRANCH" + - name: Reset to sync target branch run: | - git config --local user.email "noreply@github.com" - git config --local user.name "Github" - git merge --no-ff origin/${{ env.SYNC_TARGET_BRANCH }} + git reset --hard origin/${{ env.SYNC_TARGET_BRANCH }} - name: Create PR id: create_pr uses: peter-evans/create-pull-request@v3 with: - token: ${{ secrets.GITHUB_TOKEN }} + token: ${{ steps.generate-token.outputs.token }} commit-message: sync main for develop committer: GitHub author: GitHub @@ -60,3 +56,11 @@ jobs: run: | echo "Pull Request Number - ${{ steps.create_pr.outputs.pull-request-number }}" echo "Pull Request URL - ${{ steps.create_pr.outputs.pull-request-url }}" + + - name: Enable Auto-merge + if: steps.create_pr.outputs.pull-request-operation == 'created' + uses: peter-evans/enable-pull-request-automerge@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + pull-request-number: ${{ steps.create_pr.outputs.pull-request-number }} + merge-method: merge From fbd9fa03dc8231fdd928e9ab0c222cc41c5fb8bc Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Sat, 24 Jul 2021 13:57:03 +0900 Subject: [PATCH 183/851] Remove unnecessary lines in CI scripts (#290) Signed-off-by: Kenji Miyake --- .github/workflows/build_and_test_pr.yml | 4 ---- 1 file changed, 4 deletions(-) diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml index f9421aff4e..bdeab6cd47 100644 --- a/.github/workflows/build_and_test_pr.yml +++ b/.github/workflows/build_and_test_pr.yml @@ -4,10 +4,6 @@ on: pull_request: workflow_dispatch: -env: - BUILD_DEPEND_FILE: https://raw.githubusercontent.com/tier4/autoware.proj/main/autoware.proj.repos - SELF_REPO: tier4/autoware_launcher - jobs: build-and-test-pr: runs-on: ubuntu-latest From 7056285aa67e5a40956f5e365da0b412f08b4518 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 26 Jul 2021 00:00:04 +0900 Subject: [PATCH 184/851] Move global_params.launch.py and vehicle_info.launch.py to autoware_global_parameter_loader (#282) * Move global_params.launch.py and vehicle_info.launch.py to autoware_global_parameter_loader Signed-off-by: Kenji Miyake * Add exec_depend Signed-off-by: Kenji Miyake --- autoware_launch/launch/autoware.launch.xml | 2 +- .../launch/global_params.launch.py | 52 ------------------- .../launch/logging_simulator.launch.xml | 2 +- .../launch/planning_simulator.launch.xml | 2 +- autoware_launch/package.xml | 1 + vehicle_launch/launch/vehicle_info.launch.py | 34 ------------ 6 files changed, 4 insertions(+), 89 deletions(-) delete mode 100644 autoware_launch/launch/global_params.launch.py delete mode 100644 vehicle_launch/launch/vehicle_info.launch.py diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 8a98cb5ea5..cfede42966 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -10,7 +10,7 @@ - + diff --git a/autoware_launch/launch/global_params.launch.py b/autoware_launch/launch/global_params.launch.py deleted file mode 100644 index 4763e50496..0000000000 --- a/autoware_launch/launch/global_params.launch.py +++ /dev/null @@ -1,52 +0,0 @@ -# Copyright 2021 Tier IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.actions import IncludeLaunchDescription -from launch.actions import OpaqueFunction -from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import SetParameter -from launch_ros.substitutions import FindPackageShare - - -def launch_setup(context, *args, **kwargs): - # use_sim_time - set_use_sim_time = SetParameter(name='use_sim_time', value=LaunchConfiguration('use_sim_time')) - - # vehicle_info - vehicle_description_pkg = FindPackageShare([ - LaunchConfiguration('vehicle_model'), '_description']).perform(context) - - load_vehicle_info = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - [FindPackageShare('vehicle_launch'), '/launch/vehicle_info.launch.py'] - ), - launch_arguments={ - 'config_file': [vehicle_description_pkg, '/config/vehicle_info.param.yaml'] - }.items() - ) - - return [ - set_use_sim_time, - load_vehicle_info, - ] - - -def generate_launch_description(): - return LaunchDescription([ - DeclareLaunchArgument('use_sim_time', default_value='false'), - OpaqueFunction(function=launch_setup), - ]) diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 456542c623..19716c71f6 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -21,7 +21,7 @@ - + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index d443d49e0f..9ebfdee2e3 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -19,7 +19,7 @@ - + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index d486662a5c..6d77abb451 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -23,6 +23,7 @@ rviz2 + autoware_global_parameter_loader autoware_web_controller python-tornado python3-tornado diff --git a/vehicle_launch/launch/vehicle_info.launch.py b/vehicle_launch/launch/vehicle_info.launch.py deleted file mode 100644 index 22832f7ceb..0000000000 --- a/vehicle_launch/launch/vehicle_info.launch.py +++ /dev/null @@ -1,34 +0,0 @@ -# Copyright 2021 Tier IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.actions import OpaqueFunction -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import SetParameter -import yaml - - -def launch_setup(context, *args, **kwargs): - vehicle_param_file = LaunchConfiguration('config_file').perform(context) - with open(vehicle_param_file, 'r') as f: - vehicle_param = yaml.safe_load(f)['/**']['ros__parameters'] - return [SetParameter(name=k, value=v) for (k, v) in vehicle_param.items()] - - -def generate_launch_description(): - return LaunchDescription([ - DeclareLaunchArgument('config_file'), - OpaqueFunction(function=launch_setup), - ]) From 4b2a90adada7702c6787c6440f101b911b170e2d Mon Sep 17 00:00:00 2001 From: YamatoAndo Date: Mon, 26 Jul 2021 16:32:12 +0900 Subject: [PATCH 185/851] use_twist_with_covariance is false (#295) --- .../launch/twist_estimator/twist_estimator.launch.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml index bc9af1ca04..7bd78ae533 100644 --- a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml +++ b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml @@ -1,6 +1,7 @@ + From a5470e2027589056f8c5aa671e184730550324e5 Mon Sep 17 00:00:00 2001 From: YamatoAndo Date: Mon, 26 Jul 2021 20:44:43 +0900 Subject: [PATCH 186/851] add imu_corrector (#296) --- sensing_launch/launch/aip_customized/imu.launch.xml | 12 +++++------- sensing_launch/launch/aip_s1/imu.launch.xml | 12 +++++------- sensing_launch/launch/aip_x1/imu.launch.xml | 12 ++++++------ sensing_launch/launch/aip_x2/imu.launch.xml | 12 +++++------- sensing_launch/launch/aip_xx1/imu.launch.xml | 12 +++++------- sensing_launch/launch/aip_xx2/imu.launch.xml | 12 +++++------- 6 files changed, 31 insertions(+), 41 deletions(-) diff --git a/sensing_launch/launch/aip_customized/imu.launch.xml b/sensing_launch/launch/aip_customized/imu.launch.xml index e1eabf6ae8..c7305b6924 100644 --- a/sensing_launch/launch/aip_customized/imu.launch.xml +++ b/sensing_launch/launch/aip_customized/imu.launch.xml @@ -14,13 +14,11 @@ - - - - - - - + + + + + diff --git a/sensing_launch/launch/aip_s1/imu.launch.xml b/sensing_launch/launch/aip_s1/imu.launch.xml index e1eabf6ae8..e32d7dc97c 100644 --- a/sensing_launch/launch/aip_s1/imu.launch.xml +++ b/sensing_launch/launch/aip_s1/imu.launch.xml @@ -14,13 +14,11 @@ - - - - - - - + + + + + diff --git a/sensing_launch/launch/aip_x1/imu.launch.xml b/sensing_launch/launch/aip_x1/imu.launch.xml index d3db52ec0a..0771709bda 100644 --- a/sensing_launch/launch/aip_x1/imu.launch.xml +++ b/sensing_launch/launch/aip_x1/imu.launch.xml @@ -5,12 +5,12 @@ - - - - - - + + + + + + diff --git a/sensing_launch/launch/aip_x2/imu.launch.xml b/sensing_launch/launch/aip_x2/imu.launch.xml index e1eabf6ae8..c22b05172a 100644 --- a/sensing_launch/launch/aip_x2/imu.launch.xml +++ b/sensing_launch/launch/aip_x2/imu.launch.xml @@ -14,13 +14,11 @@ - - - - - - - + + + + + diff --git a/sensing_launch/launch/aip_xx1/imu.launch.xml b/sensing_launch/launch/aip_xx1/imu.launch.xml index e1eabf6ae8..705756e703 100644 --- a/sensing_launch/launch/aip_xx1/imu.launch.xml +++ b/sensing_launch/launch/aip_xx1/imu.launch.xml @@ -14,13 +14,11 @@ - - - - - - - + + + + + diff --git a/sensing_launch/launch/aip_xx2/imu.launch.xml b/sensing_launch/launch/aip_xx2/imu.launch.xml index e1eabf6ae8..219822bed1 100644 --- a/sensing_launch/launch/aip_xx2/imu.launch.xml +++ b/sensing_launch/launch/aip_xx2/imu.launch.xml @@ -14,13 +14,11 @@ - - - - - - - + + + + + From 8498ef47752d5848613c736dbe2605e46b5b73f1 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 27 Jul 2021 12:47:11 +0900 Subject: [PATCH 187/851] Fix CI to use Galactic (#298) Signed-off-by: Kenji Miyake --- .github/workflows/build_and_test.yml | 8 ++++---- .github/workflows/build_and_test_pr.yml | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 704a803446..fea891463b 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -8,7 +8,7 @@ on: jobs: build-and-test: runs-on: ubuntu-latest - container: osrf/ros:foxy-desktop + container: osrf/ros:galactic-desktop steps: - name: Checkout repository @@ -43,18 +43,18 @@ jobs: vcs import dependency_ws < build_depends.repos apt-get -y update rosdep update - rosdep install -y --from-paths . --ignore-src --rosdistro foxy + rosdep install -y --from-paths . --ignore-src --rosdistro galactic - name: Build run: | - . /opt/ros/foxy/setup.sh + . /opt/ros/galactic/setup.sh colcon build --event-handlers console_cohesion+ \ --packages-up-to ${{ steps.list_packages.outputs.package_list }} \ --cmake-args -DCMAKE_BUILD_TYPE=Release - name: Run tests run: | - . /opt/ros/foxy/setup.sh + . /opt/ros/galactic/setup.sh colcon test --event-handlers console_cohesion+ \ --packages-select ${{ steps.list_packages.outputs.package_list }} \ --return-code-on-test-failure diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml index bdeab6cd47..59b04a3737 100644 --- a/.github/workflows/build_and_test_pr.yml +++ b/.github/workflows/build_and_test_pr.yml @@ -7,7 +7,7 @@ on: jobs: build-and-test-pr: runs-on: ubuntu-latest - container: osrf/ros:foxy-desktop + container: osrf/ros:galactic-desktop steps: - name: Cancel previous runs @@ -51,12 +51,12 @@ jobs: vcs import dependency_ws < build_depends.repos apt-get -y update rosdep update - rosdep install -y --from-paths . --ignore-src --rosdistro foxy + rosdep install -y --from-paths . --ignore-src --rosdistro galactic - name: Build if: ${{ steps.list_packages.outputs.package_list != '' }} run: | - . /opt/ros/foxy/setup.sh + . /opt/ros/galactic/setup.sh colcon build --event-handlers console_cohesion+ \ --packages-up-to ${{ steps.list_packages.outputs.package_list }} \ --cmake-args -DCMAKE_BUILD_TYPE=Release @@ -64,7 +64,7 @@ jobs: - name: Run tests if: ${{ steps.list_packages.outputs.package_list != '' }} run: | - . /opt/ros/foxy/setup.sh + . /opt/ros/galactic/setup.sh colcon test --event-handlers console_cohesion+ \ --packages-select ${{ steps.list_packages.outputs.package_list }} \ --return-code-on-test-failure From 3fbea60ec591cccb23f6a1b437a2c7155570aa4c Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 27 Jul 2021 18:04:18 +0900 Subject: [PATCH 188/851] Add sync-upstream.yml for forks (#291) Signed-off-by: Kenji Miyake --- .github/workflows/sync-upstream.yml | 77 +++++++++++++++++++++++++++++ 1 file changed, 77 insertions(+) create mode 100644 .github/workflows/sync-upstream.yml diff --git a/.github/workflows/sync-upstream.yml b/.github/workflows/sync-upstream.yml new file mode 100644 index 0000000000..934cb0bb9f --- /dev/null +++ b/.github/workflows/sync-upstream.yml @@ -0,0 +1,77 @@ +name: sync upstream + +on: + schedule: + - cron: "0 19 * * *" # run at 4 AM JST + workflow_dispatch: + +env: + UPSTREAM_REPO: https://github.com/tier4/autoware_launcher.git + BASE_BRANCH: main + SYNC_TARGET_BRANCH: main + SYNC_BRANCH: sync-upstream + +jobs: + sync-upstream: + runs-on: ubuntu-20.04 + + steps: + - name: Checkout repository + uses: actions/checkout@v2 + with: + ref: ${{ env.BASE_BRANCH }} + fetch-depth: 0 + + - name: Generate token + uses: tibdex/github-app-token@v1 + id: generate-token + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.APP_PRIVATE_KEY }} + + - name: Set git config for private repositories + run: | + git config --local --unset-all http.https://github.com/.extraheader || true + git config --global url.https://x-access-token:${{ steps.generate-token.outputs.token }}@github.com.insteadOf 'https://github.com' + + - name: Fetch upstream + run: | + git remote add upstream "${{ env.UPSTREAM_REPO }}" + git fetch -pPtf --all + + # To keep the base branch in "create-pull-request", checkout with "BASE_BRANCH" and reset to "SYNC_TARGET_BRANCH" + - name: Reset to sync target branch + run: | + git reset --hard upstream/${{ env.SYNC_TARGET_BRANCH }} + + - name: Create PR + id: create_pr + uses: peter-evans/create-pull-request@v3 + with: + token: ${{ steps.generate-token.outputs.token }} + commit-message: sync upstream + committer: GitHub + author: GitHub + signoff: false + base: ${{ env.BASE_BRANCH }} + branch: ${{ env.SYNC_BRANCH }} + delete-branch: true + title: sync upstream + body: | + sync upstream + labels: | + sync-upstream + draft: false + + - name: Check outputs + run: | + echo "Pull Request Number - ${{ steps.create_pr.outputs.pull-request-number }}" + echo "Pull Request URL - ${{ steps.create_pr.outputs.pull-request-url }}" + + - name: Enable Auto-merge + if: steps.create_pr.outputs.pull-request-operation == 'created' + uses: peter-evans/enable-pull-request-automerge@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + pull-request-number: ${{ steps.create_pr.outputs.pull-request-number }} + merge-method: merge From 661f03c303b444c91830d3ee7c24fe0d50d0896d Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 29 Jul 2021 11:03:58 +0900 Subject: [PATCH 189/851] Fix typo applygin->applying (#304) Signed-off-by: kosuke55 --- .../obstacle_avoidance_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 2a1b0a6d06..0615aa1073 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -14,7 +14,7 @@ # clearance for unique points clearance_for_straight_line: 0.05 # minimum optimizing range around straight 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 + clearance_for_only_smoothing: 0.1 # minimum optimizing range when applying 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 From 793679b85fa5ac028311e31bbbbd9ce9b3548c21 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Fri, 30 Jul 2021 22:05:10 +0900 Subject: [PATCH 190/851] Bump styfle/cancel-workflow-action from 0.9.0 to 0.9.1 (#311) Bumps [styfle/cancel-workflow-action](https://github.com/styfle/cancel-workflow-action) from 0.9.0 to 0.9.1. - [Release notes](https://github.com/styfle/cancel-workflow-action/releases) - [Commits](https://github.com/styfle/cancel-workflow-action/compare/0.9.0...0.9.1) --- updated-dependencies: - dependency-name: styfle/cancel-workflow-action dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/build_and_test_pr.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml index 59b04a3737..4446020de7 100644 --- a/.github/workflows/build_and_test_pr.yml +++ b/.github/workflows/build_and_test_pr.yml @@ -11,7 +11,7 @@ jobs: steps: - name: Cancel previous runs - uses: styfle/cancel-workflow-action@0.9.0 + uses: styfle/cancel-workflow-action@0.9.1 - name: Checkout repository uses: actions/checkout@v2 From fbd189aea786fc25defa9d30510e0779c7af866e Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 Aug 2021 11:05:21 +0900 Subject: [PATCH 191/851] add description for map_launch #333 --- map_launch/launch/map.launch.py | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/map_launch/launch/map.launch.py b/map_launch/launch/map.launch.py index c72c85b251..925ac2fcf0 100644 --- a/map_launch/launch/map.launch.py +++ b/map_launch/launch/map.launch.py @@ -96,17 +96,19 @@ def generate_launch_description(): output='screen', ) - def add_launch_arg(name: str, default_value=None): - return DeclareLaunchArgument(name, default_value=default_value) + def add_launch_arg(name: str, default_value=None, description=None): + return DeclareLaunchArgument(name, default_value=default_value, description=description) return launch.LaunchDescription([ - add_launch_arg('map_path', ''), + add_launch_arg('map_path', '', 'path to map directory'), add_launch_arg('lanelet2_map_path', [ - LaunchConfiguration('map_path'), '/lanelet2_map.osm']), + LaunchConfiguration('map_path'), '/lanelet2_map.osm'], + 'path to lanelet2 map file'), add_launch_arg('pointcloud_map_path', [ - LaunchConfiguration('map_path'), '/pointcloud_map.pcd']), - add_launch_arg('use_intra_process', 'false'), - add_launch_arg('use_multithread', 'false'), + LaunchConfiguration('map_path'), '/pointcloud_map.pcd'], + 'path to pointcloud map file'), + add_launch_arg('use_intra_process', 'false', 'use ROS2 component container communication'), + add_launch_arg('use_multithread', 'false', 'use multithread'), SetLaunchConfiguration( 'container_executable', 'component_container', From f30548a59142264b43d6451360308327a344c436 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 Aug 2021 14:05:26 +0900 Subject: [PATCH 192/851] add description for integration_launch (#331) * add description * fix sentence --- .../launch/ci_planning_simulator.launch.xml | 14 +++++++------- integration_launch/launch/release.launch.xml | 12 ++++++------ 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/integration_launch/launch/ci_planning_simulator.launch.xml b/integration_launch/launch/ci_planning_simulator.launch.xml index ebbe82a5a9..04ea5f3b73 100644 --- a/integration_launch/launch/ci_planning_simulator.launch.xml +++ b/integration_launch/launch/ci_planning_simulator.launch.xml @@ -1,14 +1,14 @@ - - - - + + + + - - - + + + diff --git a/integration_launch/launch/release.launch.xml b/integration_launch/launch/release.launch.xml index d436a4806e..3a27a1fa20 100644 --- a/integration_launch/launch/release.launch.xml +++ b/integration_launch/launch/release.launch.xml @@ -1,12 +1,12 @@ - - - - - - + + + + + + From ae0f1078ce4ca8e13c7f9ed3643cec8300728d31 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 Aug 2021 17:31:48 +0900 Subject: [PATCH 193/851] add description for vehicle_launch (#337) * add description * delete duplicate * delete slash * fix sentence --- vehicle_launch/launch/vehicle.launch.xml | 13 ++++++------- .../launch/vehicle_description.launch.xml | 11 +++++------ vehicle_launch/launch/vehicle_interface.launch.xml | 14 +++++++------- 3 files changed, 18 insertions(+), 20 deletions(-) diff --git a/vehicle_launch/launch/vehicle.launch.xml b/vehicle_launch/launch/vehicle.launch.xml index b45f4a0f42..5b700daa6a 100644 --- a/vehicle_launch/launch/vehicle.launch.xml +++ b/vehicle_launch/launch/vehicle.launch.xml @@ -1,13 +1,12 @@ - - - + + + - - - - + + + diff --git a/vehicle_launch/launch/vehicle_description.launch.xml b/vehicle_launch/launch/vehicle_description.launch.xml index d714c27cb4..3feda41d8c 100644 --- a/vehicle_launch/launch/vehicle_description.launch.xml +++ b/vehicle_launch/launch/vehicle_description.launch.xml @@ -1,14 +1,13 @@ - - - - + + + - - + + diff --git a/vehicle_launch/launch/vehicle_interface.launch.xml b/vehicle_launch/launch/vehicle_interface.launch.xml index f7af0bfa1b..0a921aad2f 100644 --- a/vehicle_launch/launch/vehicle_interface.launch.xml +++ b/vehicle_launch/launch/vehicle_interface.launch.xml @@ -1,18 +1,18 @@ - - - - - + + + + + - + - + From fab4ee1ae4afa80cb17c21bf15094c54adc37b43 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 Aug 2021 18:11:10 +0900 Subject: [PATCH 194/851] add description for localization_launch (#332) * add description * fix sentence --- localization_launch/launch/util/util.launch.xml | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 3a7b67fb1d..8bed2b2304 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -2,19 +2,19 @@ - - - - + + + + - + - + - + From 107b93dba99469e7f771289e8fd6a7bdb5ac390d Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 Aug 2021 18:16:32 +0900 Subject: [PATCH 195/851] add description for control_launch (#330) * add description * fix sentence * use of --- control_launch/launch/control.launch.py | 54 +++++++++++++++---------- 1 file changed, 32 insertions(+), 22 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 7afe3ce2bc..e33ff7239f 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -315,50 +315,57 @@ def launch_setup(context, *args, **kwargs): 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('lateral_control_mode', 'mpc_follower') + def add_launch_arg(name: str, default_value=None, description=None): + launch_arguments.append(DeclareLaunchArgument( + name, default_value=default_value, description=description)) + add_launch_arg('lateral_control_mode', 'mpc_follower', + 'lateral control mode: `mpc_follower` or `pure_pursuit`') add_launch_arg( 'mpc_follower_param_path', [ FindPackageShare('control_launch'), '/config/mpc_follower/mpc_follower.param.yaml' - ] + ], + 'path to the parameter file of mpc_follower' ) add_launch_arg( 'pure_pursuit_param_path', [ FindPackageShare('control_launch'), '/config/pure_pursuit/pure_pursuit.param.yaml' - ] + ], + 'path to the parameter file of pure_pursuit' ) add_launch_arg( 'velocity_controller_param_path', [ FindPackageShare('control_launch'), '/config/velocity_controller/velocity_controller.param.yaml' - ] + ], + 'path to the parameter file of velocity controller' ) add_launch_arg( 'vehicle_cmd_gate_param_path', [ FindPackageShare('control_launch'), '/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml' - ] + ], + 'path to the parameter file of vehicle_cmd_gate' ) # velocity controller - add_launch_arg('control_rate', '30.0') - add_launch_arg('show_debug_info', 'false') - add_launch_arg('enable_smooth_stop', 'true') - add_launch_arg('enable_pub_debug', 'true') + add_launch_arg('control_rate', '30.0', 'control rate') + add_launch_arg('show_debug_info', 'false', 'show debug information') + add_launch_arg('enable_smooth_stop', 'true', + 'enable smooth stop (in velocity controller state)') + add_launch_arg('enable_pub_debug', 'true', 'enable to publish debug information') # vehicle cmd gate - add_launch_arg('use_emergency_handling', 'false') - add_launch_arg('use_external_emergency_stop', 'true') + add_launch_arg('use_emergency_handling', 'false', 'use emergency handling') + add_launch_arg('use_external_emergency_stop', 'true', 'use external emergency stop') # external cmd selector - add_launch_arg('initial_selector_mode', '1') + add_launch_arg('initial_selector_mode', '1', '0: Local, 1: Remote') # remote cmd converter add_launch_arg( @@ -366,22 +373,25 @@ def add_launch_arg(name: str, default_value=None): [ FindPackageShare('raw_vehicle_cmd_converter'), '/data/default/accel_map.csv' - ] + ], + 'csv file path for accel map' ) add_launch_arg( 'csv_path_brake_map', [ FindPackageShare('raw_vehicle_cmd_converter'), '/data/default/brake_map.csv' - ] + ], + 'csv file path for brake map' ) - add_launch_arg('ref_vel_gain', '3.0') - add_launch_arg('wait_for_first_topic', 'true') - add_launch_arg('control_command_timeout', '1.0') - add_launch_arg('emergency_stop_timeout', '3.0') + add_launch_arg('ref_vel_gain', '3.0', 'gain for remote command accel') + add_launch_arg('wait_for_first_topic', 'true', + 'disable topic disruption detection until subscribing first topics') + add_launch_arg('control_command_timeout', '1.0', 'remote control command timeout') + add_launch_arg('emergency_stop_timeout', '3.0', 'emergency stop timeout for remote heartbeat') - add_launch_arg('use_intra_process', 'false') - add_launch_arg('use_multithread', 'false') + add_launch_arg('use_intra_process', 'false', 'use ROS2 component container communication') + add_launch_arg('use_multithread', 'false', 'use multithread') set_container_executable = SetLaunchConfiguration( 'container_executable', 'component_container', From 524c4fc1a33f0d6406a220c8c3a13b8dc92d783a Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 Aug 2021 18:17:45 +0900 Subject: [PATCH 196/851] add description for planning_launch #335 --- .../launch/mission_planning/mission_planning.launch.py | 3 ++- planning_launch/launch/scenario_planning/parking.launch.py | 6 ++++-- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/planning_launch/launch/mission_planning/mission_planning.launch.py b/planning_launch/launch/mission_planning/mission_planning.launch.py index 2e5cf63e27..a618e55bed 100644 --- a/planning_launch/launch/mission_planning/mission_planning.launch.py +++ b/planning_launch/launch/mission_planning/mission_planning.launch.py @@ -64,6 +64,7 @@ def generate_launch_description(): ], ) return launch.LaunchDescription([ - DeclareLaunchArgument('use_intra_process', default_value='false'), + DeclareLaunchArgument('use_intra_process', default_value='false', + description='use ROS2 component container communication'), container ]) diff --git a/planning_launch/launch/scenario_planning/parking.launch.py b/planning_launch/launch/scenario_planning/parking.launch.py index d831a3bcd4..0cbdd7a270 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.py +++ b/planning_launch/launch/scenario_planning/parking.launch.py @@ -128,8 +128,10 @@ def generate_launch_description(): ) return launch.LaunchDescription([ - DeclareLaunchArgument('use_intra_process', default_value='false'), - DeclareLaunchArgument('use_multithread', default_value='false'), + DeclareLaunchArgument('use_intra_process', default_value='false', + description='use ROS2 component container communication'), + DeclareLaunchArgument('use_multithread', default_value='false', + description='use multithread'), set_container_executable, set_container_mt_executable, GroupAction([ From aaf6ea690d63f100e6f783483a06e75c49f94f40 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 Aug 2021 18:18:09 +0900 Subject: [PATCH 197/851] add description for sensing_launch (#336) * add description * fix sentence --- sensing_launch/launch/sensing.launch.xml | 8 ++-- .../launch/velodyne_node_container.launch.py | 40 ++++++++++--------- 2 files changed, 25 insertions(+), 23 deletions(-) diff --git a/sensing_launch/launch/sensing.launch.xml b/sensing_launch/launch/sensing.launch.xml index 946d83ed26..91bc779575 100644 --- a/sensing_launch/launch/sensing.launch.xml +++ b/sensing_launch/launch/sensing.launch.xml @@ -1,9 +1,9 @@ - - - - + + + + diff --git a/sensing_launch/launch/velodyne_node_container.launch.py b/sensing_launch/launch/velodyne_node_container.launch.py index 7f4a3ec7b2..36007734cc 100644 --- a/sensing_launch/launch/velodyne_node_container.launch.py +++ b/sensing_launch/launch/velodyne_node_container.launch.py @@ -187,37 +187,39 @@ def create_parameter_dict(*args): def generate_launch_description(): launch_arguments = [] - def add_launch_arg(name: str, default_value=None): + def add_launch_arg(name: str, default_value=None, description=None): # a default_value of None is equivalent to not passing that kwarg at all - launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + launch_arguments.append(DeclareLaunchArgument( + name, default_value=default_value, description=description)) - 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('model', description='velodyne model name') + add_launch_arg('launch_driver', 'True', 'do launch driver') + add_launch_arg('calibration', description='path to calibration file') + add_launch_arg('device_ip', '192.168.1.201', 'device ip address') 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('base_frame', 'base_link', 'base frame id') + add_launch_arg('container_name', 'velodyne_composable_node_container', 'container name') + add_launch_arg('min_range', description='minimum view range') + add_launch_arg('max_range', description='maximum view range') add_launch_arg('pcap', '') - add_launch_arg('port', '2368') + add_launch_arg('port', '2368', description='device port number') 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('rpm', '600.0', 'rotational frequency') 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('frame_id', 'velodyne', 'velodyne frame id') add_launch_arg('gps_time', 'False') - add_launch_arg('input_frame', LaunchConfiguration('base_frame')) - add_launch_arg('output_frame', LaunchConfiguration('base_frame')) - add_launch_arg('vehicle_param_file') - add_launch_arg('vehicle_mirror_param_file') - add_launch_arg('use_multithread', 'False') - add_launch_arg('use_intra_process', 'False') + add_launch_arg('input_frame', LaunchConfiguration('base_frame'), 'use for cropbox') + add_launch_arg('output_frame', LaunchConfiguration('base_frame'), 'use for cropbox') + add_launch_arg('vehicle_param_file', description='path to the file of vehicle info yaml') + add_launch_arg('vehicle_mirror_param_file', + description='path to the file of vehicle mirror position yaml') + add_launch_arg('use_multithread', 'False', 'use multithread') + add_launch_arg('use_intra_process', 'False', 'use ROS2 component container communication') set_container_executable = SetLaunchConfiguration( 'container_executable', From fe9b3b2a24ce78b1934cb3cf52434f3f670c916d Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 Aug 2021 18:20:09 +0900 Subject: [PATCH 198/851] add description for perception (#334) --- .../camera_lidar_fusion_based_detection.launch.xml | 8 ++++---- .../object_recognition/detection/detection.launch.xml | 10 +++++----- .../detection/lidar_based_detection.launch.xml | 2 +- .../prediction/prediction.launch.xml | 2 +- perception_launch/launch/perception.launch.xml | 11 +++++------ .../traffic_light.launch.xml | 6 +++--- .../traffic_light_node_container.launch.py | 5 +++-- 7 files changed, 22 insertions(+), 22 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 8c6ced37f6..2ce4d2d216 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 @@ -1,8 +1,8 @@ - - + + @@ -17,8 +17,8 @@ - - + + - - + + @@ -19,8 +19,8 @@ - - + + 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 0f45cc31ca..1f5853ba43 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,6 +1,6 @@ - + diff --git a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml index 848b17ab9d..99f0b1e0cb 100644 --- a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml +++ b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml @@ -1,7 +1,7 @@ - + diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 193e7066e3..3cbb396bab 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -2,10 +2,9 @@ - - - - + + + @@ -20,8 +19,8 @@ - - + + 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 eb1f6cf843..d86a8ccf19 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -1,9 +1,9 @@ - - - + + + 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 8204a86a8f..2600c0c2b0 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 @@ -30,9 +30,10 @@ def generate_launch_description(): launch_arguments = [] - def add_launch_arg(name: str, default_value=None): + def add_launch_arg(name: str, default_value=None, description=None): # a default_value of None is equivalent to not passing that kwarg at all - launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + launch_arguments.append(DeclareLaunchArgument( + name, default_value=default_value, description=description)) ssd_fine_detector_share_dir = get_package_share_directory( 'traffic_light_ssd_fine_detector' From c7d9f0c1e2c06d8aed5db87998f40d49994a7b01 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 Aug 2021 18:21:11 +0900 Subject: [PATCH 199/851] add descriptions for autoware_launch #329 --- autoware_launch/launch/autoware.launch.xml | 8 ++++---- .../launch/logging_simulator.launch.xml | 10 +++++----- .../launch/planning_simulator.launch.xml | 20 +++++++++---------- 3 files changed, 19 insertions(+), 19 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index cfede42966..2ca581432f 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -2,12 +2,12 @@ - - + + - - + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 19716c71f6..610c932752 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -3,9 +3,9 @@ - - - + + + @@ -17,8 +17,8 @@ - - + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 9ebfdee2e3..22a094a20d 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -2,21 +2,21 @@ - - + + - - + + - - - - - + + + + + - + From d8804742afe903db7172eee645ddc59704b6a93c Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Thu, 12 Aug 2021 18:24:12 +0900 Subject: [PATCH 200/851] Add matrix CI to build_and_test.yml (#338) Signed-off-by: Kenji Miyake --- .github/workflows/build_and_test.yml | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index fea891463b..008504b60e 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -8,11 +8,19 @@ on: jobs: build-and-test: runs-on: ubuntu-latest + strategy: + fail-fast: false + matrix: + branch: + - main + - develop container: osrf/ros:galactic-desktop steps: - name: Checkout repository uses: actions/checkout@v2 + with: + ref: ${{ matrix.branch }} - name: Install pip run: | From 462b2819a4e1ed67acacb3252b714feb4fcff762 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 Aug 2021 21:13:22 +0900 Subject: [PATCH 201/851] add README.md and svg files (#328) * add md and svg * fix typo * fix typo * fix word * fix typo * add lack of things * Update README * fix depending packages * fix word --- README.md | 28 +- autoware_launch/README.md | 17 + autoware_launch/autoware_launch.drawio.svg | 1375 +++++++++++++++++ control_launch/README.md | 24 + control_launch/control_launch.drawio.svg | 421 +++++ integration_launch/README.md | 14 + .../integration_launch.drawio.svg | 228 +++ localization_launch/README.md | 26 + .../localization_launch.drawio.svg | 530 +++++++ map_launch/README.md | 28 + map_launch/map_launch.drawio.svg | 250 +++ perception_launch/README.md | 21 + .../perception_launch.drawio.svg | 309 ++++ planning_launch/README.md | 16 + planning_launch/planning_launch.drawio.svg | 318 ++++ sensing_launch/README.md | 49 + sensing_launch/sensing_launch.drawio.svg | 228 +++ system_launch/README.md | 17 + system_launch/system_launch.drawio.svg | 434 ++++++ vehicle_launch/README.md | 70 + vehicle_launch/vehicle_launch.drawio.svg | 442 ++++++ 21 files changed, 4844 insertions(+), 1 deletion(-) create mode 100644 autoware_launch/README.md create mode 100644 autoware_launch/autoware_launch.drawio.svg create mode 100644 control_launch/README.md create mode 100644 control_launch/control_launch.drawio.svg create mode 100644 integration_launch/README.md create mode 100644 integration_launch/integration_launch.drawio.svg create mode 100644 localization_launch/README.md create mode 100644 localization_launch/localization_launch.drawio.svg create mode 100644 map_launch/README.md create mode 100644 map_launch/map_launch.drawio.svg create mode 100644 perception_launch/README.md create mode 100644 perception_launch/perception_launch.drawio.svg create mode 100644 planning_launch/README.md create mode 100644 planning_launch/planning_launch.drawio.svg create mode 100644 sensing_launch/README.md create mode 100644 sensing_launch/sensing_launch.drawio.svg create mode 100644 system_launch/README.md create mode 100644 system_launch/system_launch.drawio.svg create mode 100644 vehicle_launch/README.md create mode 100644 vehicle_launch/vehicle_launch.drawio.svg diff --git a/README.md b/README.md index a895a99a59..94519ba3a9 100644 --- a/README.md +++ b/README.md @@ -1,2 +1,28 @@ # autoware_launcher -launch files for autoware + +## Getting Started + +### Using real vehicle + +```bash +ros2 launch autoware_launch autoware.launch.xml map_path:=/path/to/map_folder vehicle_model:=[vehicle_name] sensor_model:=[sensor_name] +``` + +### Using planning simulator + +```bash +ros2 launch autoware_launch planning_simulator.launch.xml map_path:=/path/to/map_folder vehicle_model:=[vehicle_name] sensor_model:=[sensor_name] +``` + +## Directory Structure + +- [autoware_launch](./autoware_launch) +- [control_launch](./control_launch) +- [integration_launch](./integration_launch) +- [localization_launch](./localization_launch) +- [map_launch](./map_launch) +- [perception_launch](./perception_launch) +- [planning_launch](./planning_launch) +- [sensing_launch](./sensing_launch) +- [system_launch](./system_launch) +- [vehicle_launch](./vehicle_launch) diff --git a/autoware_launch/README.md b/autoware_launch/README.md new file mode 100644 index 0000000000..61f7f4a3b7 --- /dev/null +++ b/autoware_launch/README.md @@ -0,0 +1,17 @@ +# autoware_launch + +## Structure + +![autoware_launch](./autoware_launch.drawio.svg) + +## Package Dependencies + +Please see `` in `package.xml`. + +## Usage + +You can use the command as follows at shell script to launch `*.launch.xml` in `launch` directory. + +```bash +ros2 launch autoware_launch autoware.launch.xml map_path:=/path/to/map_folder vehicle_model:=lexus sensor_model:=aip_xx1 +``` diff --git a/autoware_launch/autoware_launch.drawio.svg b/autoware_launch/autoware_launch.drawio.svg new file mode 100644 index 0000000000..5c435ce4f4 --- /dev/null +++ b/autoware_launch/autoware_launch.drawio.svg @@ -0,0 +1,1375 @@ + + + + + + + +
    +
    +
    + autoware.launch.xml +
    +
    +
    + + package: autoware_launch + +
    +
    +
    +
    +
    + + autoware.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + launch name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + launch name... + +
    +
    + + + + +
    +
    +
    + ex: +
    +
    +
    +
    + + ex: + +
    +
    + + + + +
    +
    +
    + node name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + node name... + +
    +
    + + + + +
    +
    +
    + vehicle_info_launch.py +
    +
    +
    + + package: vehicle_launch + +
    +
    +
    +
    +
    + + vehicle_info_launch.py... + +
    +
    + + + + +
    +
    +
    + vehicle.launch.xml +
    +
    +
    + + package: vehicle_launch + +
    +
    +
    +
    +
    + + vehicle.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + system.launch.xml +
    +
    +
    + + package: system_launch + +
    +
    +
    +
    +
    + + system.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + map.launch.py +
    +
    +
    + + package: map_launch + +
    +
    +
    +
    +
    + + map.launch.py... + +
    +
    + + + + + + +
    +
    +
    + localization.launch.xml +
    +
    +
    + + package: localization_launch + +
    +
    +
    +
    +
    + + localization.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + perception.launch.xml +
    +
    +
    + + package: perception_launch + +
    +
    +
    +
    +
    + + perception.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + planning.launch.xml +
    +
    +
    + + package: planning_launch + +
    +
    +
    +
    +
    + + planning.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + control.launch.py +
    +
    +
    + + package: control_launch + +
    +
    +
    +
    +
    + + control.launch.py... + +
    +
    + + + + + + +
    +
    +
    + awapi_awiv_adapter.launch.xml +
    +
    +
    + + package: control_launch + +
    +
    +
    +
    +
    + + awapi_awiv_adapter.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + autoware_web_controller.launch.xml +
    +
    +
    + + package: control_launch + +
    +
    +
    +
    +
    + + autoware_web_controller.launch.xml... + +
    +
    + + + + +
    +
    +
    + clock_publisher.launch.xml +
    +
    +
    + + package: control_launch + +
    +
    +
    +
    +
    + + clock_publisher.launch.xml... + +
    +
    + + + + + + + + +
    +
    +
    + rviz2 +
    +
    +
    + + package: rviz2 + +
    +
    +
    +
    +
    + + rviz2... + +
    +
    + + + + + + +
    +
    +
    + planning_simulator.xml +
    +
    +
    + + package: autoware_launch + +
    +
    +
    +
    +
    + + planning_simulator.xml... + +
    +
    + + + + + + +
    +
    +
    + vehicle_info_launch.py +
    +
    +
    + + package: vehicle_launch + +
    +
    +
    +
    +
    + + vehicle_info_launch.py... + +
    +
    + + + + +
    +
    +
    + vehicle.launch.xml +
    +
    +
    + + package: vehicle_launch + +
    +
    +
    +
    +
    + + vehicle.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + system.launch.xml +
    +
    +
    + + package: system_launch + +
    +
    +
    +
    +
    + + system.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + map.launch.py +
    +
    +
    + + package: map_launch + +
    +
    +
    +
    +
    + + map.launch.py... + +
    +
    + + + + + + + + +
    +
    +
    + planning.launch.xml +
    +
    +
    + + package: planning_launch + +
    +
    +
    +
    +
    + + planning.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + control.launch.py +
    +
    +
    + + package: control_launch + +
    +
    +
    +
    +
    + + control.launch.py... + +
    +
    + + + + + + +
    +
    +
    + awapi_awiv_adapter.launch.xml +
    +
    +
    + + package: control_launch + +
    +
    +
    +
    +
    + + awapi_awiv_adapter.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + autoware_web_controller.launch.xml +
    +
    +
    + + package: control_launch + +
    +
    +
    +
    +
    + + autoware_web_controller.launch.xml... + +
    +
    + + + + +
    +
    +
    + clock_publisher.launch.xml +
    +
    +
    + + package: control_launch + +
    +
    +
    +
    +
    + + clock_publisher.launch.xml... + +
    +
    + + + + + + + + +
    +
    +
    + rviz2 +
    +
    +
    + + package: rviz2 + +
    +
    +
    +
    +
    + + rviz2... + +
    +
    + + + + + + +
    +
    +
    + $(var scenario_simulation) +
    +
    +
    +
    + + $(var scenario_simulation) + +
    +
    + + + + + +
    +
    +
    + False +
    +
    +
    +
    + + False + +
    +
    + + + + +
    +
    +
    + dummy_perception_publisher.launch.xml +
    +
    +
    + + package: dummy_perception_publisher + +
    +
    +
    +
    +
    + + dummy_perception_publisher.launch.xml... + +
    +
    + + + + +
    +
    +
    + logging_simulator.launch.xml +
    +
    +
    + + package: autoware_launch + +
    +
    +
    +
    +
    + + logging_simulator.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + vehicle_info_launch.py +
    +
    +
    + + package: vehicle_launch + +
    +
    +
    +
    +
    + + vehicle_info_launch.py... + +
    +
    + + + + +
    +
    +
    + vehicle_description.launch.xml +
    +
    +
    + + package: vehicle_launch + +
    +
    +
    +
    +
    + + vehicle_description.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + system.launch.xml +
    +
    +
    + + package: system_launch + +
    +
    +
    +
    +
    + + system.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + map.launch.py +
    +
    +
    + + package: map_launch + +
    +
    +
    +
    +
    + + map.launch.py... + +
    +
    + + + + + + + + +
    +
    +
    + perception.launch.xml +
    +
    +
    + + package: perception_launch + +
    +
    +
    +
    +
    + + perception.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + planning.launch.xml +
    +
    +
    + + package: planning_launch + +
    +
    +
    +
    +
    + + planning.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + control.launch.py +
    +
    +
    + + package: control_launch + +
    +
    +
    +
    +
    + + control.launch.py... + +
    +
    + + + + + + +
    +
    +
    + autoware_web_controller.launch.xml +
    +
    +
    + + package: control_launch + +
    +
    +
    +
    +
    + + autoware_web_controller.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + rviz2 +
    +
    +
    + + package: rviz2 + +
    +
    +
    +
    +
    + + rviz2... + +
    +
    + + + + + + +
    +
    +
    + $(var vehicle) +
    +
    +
    +
    + + $(var vehicle) + +
    +
    + + + + + +
    +
    +
    + True +
    +
    +
    +
    + + True + +
    +
    + + + + +
    +
    +
    + $(var system) +
    +
    +
    +
    + + $(var system) + +
    +
    + + + + + +
    +
    +
    + True +
    +
    +
    +
    + + True + +
    +
    + + + + +
    +
    +
    + $(var map) +
    +
    +
    +
    + + $(var map) + +
    +
    + + + + + +
    +
    +
    + True +
    +
    +
    +
    + + True + +
    +
    + + + + +
    +
    +
    + sensing.launch.xml +
    +
    +
    + + package: sensing_launch + +
    +
    +
    +
    +
    + + sensing.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + sensing.launch.xml +
    +
    +
    + + package: sensing_launch + +
    +
    +
    +
    +
    + + sensing.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + $(var sensing) +
    +
    +
    +
    + + $(var sensing) + +
    +
    + + + + + +
    +
    +
    + True +
    +
    +
    +
    + + True + +
    +
    + + + + +
    +
    +
    + localization.launch.xml +
    +
    +
    + + package: localization_launch + +
    +
    +
    +
    +
    + + localization.launch.xml... + +
    +
    + + + + +
    +
    +
    + $(var localization) +
    +
    +
    +
    + + $(var localization) + +
    +
    + + + + + +
    +
    +
    + True +
    +
    +
    +
    + + True + +
    +
    + + + + +
    +
    +
    + $(var perception) +
    +
    +
    +
    + + $(var perception) + +
    +
    + + + + + +
    +
    +
    + True +
    +
    +
    +
    + + True + +
    +
    + + + + +
    +
    +
    + $(var planning) +
    +
    +
    +
    + + $(var planning) + +
    +
    + + + + + +
    +
    +
    + True +
    +
    +
    +
    + + True + +
    +
    + + + + +
    +
    +
    + $(var control) +
    +
    +
    +
    + + $(var control) + +
    +
    + + + + + +
    +
    +
    + True +
    +
    +
    +
    + + True + +
    +
    +
    + + + + + Viewer does not support full SVG 1.1 + + + +
    \ No newline at end of file diff --git a/control_launch/README.md b/control_launch/README.md new file mode 100644 index 0000000000..f18eedc3c9 --- /dev/null +++ b/control_launch/README.md @@ -0,0 +1,24 @@ +# control_launch + +## Structure + +![control_launch](./control_launch.drawio.svg) + +## Package Dependencies + +Please see `` in `package.xml`. + +## Usage + +You can include as follows in `*.launch.xml` to use `control.launch.py`. + +```xml + + + + +``` + +## Notes + +For reducing processing load, we use the [Component](https://docs.ros.org/en/galactic/Concepts/About-Composition.html) feature in ROS2 (similar to Nodelet in ROS1 ) diff --git a/control_launch/control_launch.drawio.svg b/control_launch/control_launch.drawio.svg new file mode 100644 index 0000000000..82361e0a24 --- /dev/null +++ b/control_launch/control_launch.drawio.svg @@ -0,0 +1,421 @@ + + + + + + + +
    +
    +
    + container +
    +
    +
    + + package: rclcpp_components + +
    +
    +
    +
    +
    + + container... + +
    +
    + + + + +
    +
    +
    + control.launch.py +
    +
    +
    + + package: control_launch + +
    +
    +
    +
    +
    + + control.launch.py... + +
    +
    + + + + + + + +
    +
    +
    + mpc_follower +
    +
    +
    +
    + + mpc_follower + +
    +
    + + + + + +
    +
    +
    + pure_pursuit +
    +
    +
    +
    + + pure_pursuit + +
    +
    + + + + +
    +
    +
    + $(var lateral_control_mode) +
    +
    +
    +
    + + $(var lateral_control_mode) + +
    +
    + + + + +
    +
    +
    + launch name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + launch name... + +
    +
    + + + + +
    +
    +
    + ex: +
    +
    +
    +
    + + ex: + +
    +
    + + + + +
    +
    +
    + node name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + node name... + +
    +
    + + + + +
    +
    +
    + latlon_muxer +
    +
    +
    + + package: latlon_muxer + +
    +
    +
    +
    +
    + + latlon_muxer... + +
    +
    + + + + +
    +
    +
    + mpc_follower +
    +
    +
    + + package: mpc_follower + +
    +
    +
    +
    +
    + + mpc_follower... + +
    +
    + + + + +
    +
    +
    + pure_pursuit +
    +
    +
    + + package: pure_pursuit + +
    +
    +
    +
    +
    + + pure_pursuit... + +
    +
    + + + + +
    +
    +
    + velocity_controller +
    +
    +
    + + package: velocity_controller + +
    +
    +
    +
    +
    + + velocity_controller... + +
    +
    + + + + +
    +
    +
    + lane_departure_checker_node +
    +
    +
    + + package: lane_departure_checker_node + +
    +
    +
    +
    +
    + + lane_departure_checker_node... + +
    +
    + + + + +
    +
    +
    + shift_decider +
    +
    +
    + + package: shift_decider + +
    +
    +
    +
    +
    + + shift_decider... + +
    +
    + + + + +
    +
    +
    + vehicle_cmd_gate +
    +
    +
    + + package: vehicle_cmd_gate + +
    +
    +
    +
    +
    + + vehicle_cmd_gate... + +
    +
    + + + + +
    +
    +
    + remote_cmd_converter +
    +
    +
    + + package: remote_cmd_converter + +
    +
    +
    +
    +
    + + remote_cmd_converter... + +
    +
    + + + + +
    +
    +
    + external_cmd_selector +
    +
    +
    + + package: external_cmd_selector + +
    +
    +
    +
    +
    + + external_cmd_selector... + +
    +
    + + + + +
    +
    +
    + other name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + other name... + +
    +
    +
    + + + + + Viewer does not support full SVG 1.1 + + + +
    diff --git a/integration_launch/README.md b/integration_launch/README.md new file mode 100644 index 0000000000..4a58b1b467 --- /dev/null +++ b/integration_launch/README.md @@ -0,0 +1,14 @@ +# integration_launch + +## Structure + +![integration_launch](./integration_launch.drawio.svg) + +## Package Dependencies + +- autoware_launch +- scenario_runner + +## Notes + +This package is only used for continuous integration. diff --git a/integration_launch/integration_launch.drawio.svg b/integration_launch/integration_launch.drawio.svg new file mode 100644 index 0000000000..f40a0b345c --- /dev/null +++ b/integration_launch/integration_launch.drawio.svg @@ -0,0 +1,228 @@ + + + + + + + +
    +
    +
    + ci_planning_simulator.launch.xml +
    +
    +
    + + package: integration_launch + +
    +
    +
    +
    +
    + + ci_planning_simulator.launch.xml... + +
    +
    + + + + +
    +
    +
    + launch name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + launch name... + +
    +
    + + + + +
    +
    +
    + ex: +
    +
    +
    +
    + + ex: + +
    +
    + + + + +
    +
    +
    + node name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + node name... + +
    +
    + + + + +
    +
    +
    + planning_simulator.launch.xml +
    +
    +
    + + package: autoware_launch + +
    +
    +
    +
    +
    + + planning_simulator.launch.xml... + +
    +
    + + + + +
    +
    +
    + other name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + other name... + +
    +
    + + + + + + +
    +
    +
    + scenario_runner.launch.xml +
    +
    +
    + + package: scenario_runner + +
    +
    +
    +
    +
    + + scenario_runner.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + release.launch.xml +
    +
    +
    + + package: integration_launch + +
    +
    +
    +
    +
    + + release.launch.xml... + +
    +
    + + + + +
    +
    +
    + autoware.launch.xml +
    +
    +
    + + package: autoware_launch + +
    +
    +
    +
    +
    + + autoware.launch.xml... + +
    +
    + + +
    + + + + + Viewer does not support full SVG 1.1 + + + +
    \ No newline at end of file diff --git a/localization_launch/README.md b/localization_launch/README.md new file mode 100644 index 0000000000..959768012c --- /dev/null +++ b/localization_launch/README.md @@ -0,0 +1,26 @@ +# localization_launch + +## Structure + +![localization_launch](./localization_launch.drawio.svg) + +## Package Dependencies + +Please see `` in `package.xml`. + +## Usage + +You can include as follows in `*.launch.xml` to use `localization.launch.xml`. + +```xml + + +``` + +## Notes + +There are some `param.yaml` files in `config` directory. + +```bash +ndt_scan_matcher.param.yaml +``` diff --git a/localization_launch/localization_launch.drawio.svg b/localization_launch/localization_launch.drawio.svg new file mode 100644 index 0000000000..1bde302430 --- /dev/null +++ b/localization_launch/localization_launch.drawio.svg @@ -0,0 +1,530 @@ + + + + + + + +
    +
    +
    + /sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container +
    +
    +
    + + package: rclcpp_components + +
    +
    +
    +
    +
    + + /sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container... + +
    +
    + + + + +
    +
    +
    + localization.launch.xml +
    +
    +
    + + package: localization + + + _launch + +
    +
    +
    +
    +
    + + localization.launch.xml... + +
    +
    + + + + + + + + +
    +
    +
    + util.launch.xml +
    +
    +
    + package: localization_launch +
    +
    +
    +
    +
    + + util.launch.xml... + +
    +
    + + + + + + + + +
    +
    +
    + pose_estimator.launch.xml +
    +
    +
    + + package: localization_launch + +
    +
    +
    +
    +
    + + pose_estimator.launch.xml... + +
    +
    + + + + +
    +
    +
    + launch name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + launch name... + +
    +
    + + + + +
    +
    +
    + ex: +
    +
    +
    +
    + + ex: + +
    +
    + + + + +
    +
    +
    + node name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + node name... + +
    +
    + + + + +
    +
    +
    + other name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + other name... + +
    +
    + + + + + + +
    +
    +
    + twist_estimator.launch.xml +
    +
    +
    + + package: localization_launch + +
    +
    +
    +
    +
    + + twist_estimator.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + pose_twist_fusion_filter.launch.xml +
    +
    +
    + + package: localization_launch + +
    +
    +
    +
    +
    + + pose_twist_fusion_filter.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + localization_error_monitor.launch.xml +
    +
    +
    + + package: localization_error_monitor + +
    +
    +
    +
    +
    + + localization_error_monitor.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + relay +
    +
    +
    + + package: topic_tools + +
    +
    + +
    +
    +
    +
    + + input: /localization/pose_twist_fusion_filter/twist + +
    +
    + + output: /localization/twist + +
    +
    +
    +
    +
    + + relay... + +
    +
    + + + + + + +
    +
    +
    + ndt_scan_matcher.launch.xml +
    +
    +
    + + package: ndt_scan_matcher + +
    +
    +
    +
    +
    + + ndt_scan_matcher.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + gyro_odometer.launch.xml +
    +
    +
    + + package: gyro_odometer + +
    +
    +
    +
    +
    + + gyro_odometer.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + ekf_localizer.launch.xml +
    +
    +
    + + package: ekf_localizer + +
    +
    +
    +
    +
    + + ekf_localizer.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + pose_initializer.launch.xml +
    +
    +
    + + package: pose_initializer + +
    +
    +
    +
    +
    + + pose_initializer.launch.xml... + +
    +
    + + + + +
    +
    +
    + util.launch.py +
    +
    +
    + + package: localization_launch + +
    +
    +
    +
    +
    + + util.launch.py... + +
    +
    + + + + + + +
    +
    +
    + crop_box_measurement_range +
    +
    +
    + + package: pointcloud_preprocessor + +
    +
    +
    +
    +
    + + crop_box_measurement_range... + +
    +
    + + + + +
    +
    +
    + voxel_grid_downsample_filter +
    +
    +
    + + package: pointcloud_preprocessor + +
    +
    +
    +
    +
    + + voxel_grid_downsample_filter... + +
    +
    + + + + +
    +
    +
    + random_downsample_filter +
    +
    +
    + + package: pointcloud_preprocessor + +
    +
    +
    +
    +
    + + random_downsample_filter... + +
    +
    + + +
    + + + + + Viewer does not support full SVG 1.1 + + + +
    diff --git a/map_launch/README.md b/map_launch/README.md new file mode 100644 index 0000000000..5b36fb8e4b --- /dev/null +++ b/map_launch/README.md @@ -0,0 +1,28 @@ +# map_launch + +## Structure + +![map_launch](./map_launch.drawio.svg) + +## Package Dependencies + +Please see `` in `package.xml`. + +## Usage + +You can include as follows in `*.launch.xml` to use `map.launch.py`. + +```xml + + + + + + + + +``` + +## Notes + +For reducing processing load, we use the [Component](https://docs.ros.org/en/galactic/Concepts/About-Composition.html) feature in ROS2 (similar to Nodelet in ROS1 ) diff --git a/map_launch/map_launch.drawio.svg b/map_launch/map_launch.drawio.svg new file mode 100644 index 0000000000..c037a46c14 --- /dev/null +++ b/map_launch/map_launch.drawio.svg @@ -0,0 +1,250 @@ + + + + + + + +
    +
    +
    + map_container +
    +
    +
    + + package: rclcpp_components + +
    +
    +
    +
    +
    + + map_container... + +
    +
    + + + + +
    +
    +
    + map.launch.py +
    +
    +
    + + package: map_launch + +
    +
    +
    +
    +
    + + map.launch.py... + +
    +
    + + + + + + +
    +
    +
    + launch name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + launch name... + +
    +
    + + + + +
    +
    +
    + ex: +
    +
    +
    +
    + + ex: + +
    +
    + + + + +
    +
    +
    + node name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + node name... + +
    +
    + + + + +
    +
    +
    + other name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + other name... + +
    +
    + + + + +
    +
    +
    + lanelet2_map_loader +
    +
    +
    + + package: map_loader + +
    +
    +
    +
    +
    + + lanelet2_map_loader... + +
    +
    + + + + +
    +
    +
    + lanelet2_map_visualization +
    +
    +
    + + package: map_loader + +
    +
    +
    +
    +
    + + lanelet2_map_visualization... + +
    +
    + + + + +
    +
    +
    + pointcloud_map_loader +
    +
    +
    + + package: map_loader + +
    +
    +
    +
    +
    + + pointcloud_map_loader... + +
    +
    + + + + +
    +
    +
    + + map_tf_generator + +
    +
    +
    + + package: map_tf_generator + +
    +
    +
    +
    +
    + + map_tf_generator... + +
    +
    +
    + + + + + Viewer does not support full SVG 1.1 + + + +
    \ No newline at end of file diff --git a/perception_launch/README.md b/perception_launch/README.md new file mode 100644 index 0000000000..4040422890 --- /dev/null +++ b/perception_launch/README.md @@ -0,0 +1,21 @@ +# perception_launch + +## Structure + +![perception_launch](./perception_launch.drawio.svg) + +## Package Dependencies + +Please see `` in `package.xml`. + +## Usage + +You can include as follows in `*.launch.xml` to use `perception.launch.xml`. + + +```xml + + + + +``` diff --git a/perception_launch/perception_launch.drawio.svg b/perception_launch/perception_launch.drawio.svg new file mode 100644 index 0000000000..fc19d039ab --- /dev/null +++ b/perception_launch/perception_launch.drawio.svg @@ -0,0 +1,309 @@ + + + + + + + + + + + +
    +
    +
    + perception.launch.xml +
    +
    +
    + + package: perception_launch + +
    +
    +
    +
    +
    + + perception.launch.xml... + +
    +
    + + + + + + + +
    +
    +
    + False +
    +
    +
    +
    + + False + +
    +
    + + + + + + +
    +
    +
    + launch name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + launch name... + +
    +
    + + + + +
    +
    +
    + ex: +
    +
    +
    +
    + + ex: + +
    +
    + + + + +
    +
    +
    + node name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + node name... + +
    +
    + + + + +
    +
    +
    + other name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + other name... + +
    +
    + + + + +
    +
    +
    + $(var use_empty_dynamic_object_publisher) +
    +
    +
    +
    + + $(var use_empty_dynamic_object_publisher) + +
    +
    + + + + +
    +
    +
    + detection.launch.xml +
    +
    +
    + + package: perception_launch + +
    +
    +
    +
    +
    + + detection.launch.xml... + +
    +
    + + + + + +
    +
    +
    + True +
    +
    +
    +
    + + True + +
    +
    + + + + +
    +
    +
    + tracking.launch.xml +
    +
    +
    + + package: perception_launch + +
    +
    +
    +
    +
    + + tracking.launch.xml... + +
    +
    + + + + +
    +
    +
    + prediction.launch.xml +
    +
    +
    + + package: perception_launch + +
    +
    +
    +
    +
    + + prediction.launch.xml... + +
    +
    + + + + +
    +
    +
    + empty_objects_publisher +
    +
    +
    + + package: dummy_perception_publisher + +
    +
    +
    +
    +
    + + empty_objects_publisher... + +
    +
    + + + + +
    +
    +
    + traffic_light_recognition.launch.xml +
    +
    +
    + + package: perception_launch + +
    +
    +
    +
    +
    + + traffic_light_recognition.launch.xml... + +
    +
    + + +
    + + + + + Viewer does not support full SVG 1.1 + + + +
    \ No newline at end of file diff --git a/planning_launch/README.md b/planning_launch/README.md new file mode 100644 index 0000000000..84bf70d26b --- /dev/null +++ b/planning_launch/README.md @@ -0,0 +1,16 @@ +# planning_launch + +## Structure + +![planning_launch](./planning_launch.drawio.svg) + +## Package Dependencies + +Please see `` in `package.xml`. + +## Usage + +```xml + + +``` diff --git a/planning_launch/planning_launch.drawio.svg b/planning_launch/planning_launch.drawio.svg new file mode 100644 index 0000000000..fba2aefed5 --- /dev/null +++ b/planning_launch/planning_launch.drawio.svg @@ -0,0 +1,318 @@ + + + + + + + +
    +
    +
    + planning.launch.xml +
    +
    +
    + + package: planning_launch + +
    +
    +
    +
    +
    + + planning.launch.xml... + +
    +
    + + + + +
    +
    +
    + mission_planning.launch.py +
    +
    +
    + package: planning_launch +
    +
    +
    +
    +
    + + mission_planning.launch.py... + +
    +
    + + + + + + + + +
    +
    +
    + launch name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + launch name... + +
    +
    + + + + +
    +
    +
    + ex: +
    +
    +
    +
    + + ex: + +
    +
    + + + + +
    +
    +
    + node name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + node name... + +
    +
    + + + + +
    +
    +
    + other name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + other name... + +
    +
    + + + + +
    +
    +
    + scenario_planning.launch.xml +
    +
    +
    + package: planning_launch +
    +
    +
    +
    +
    + + scenario_planning.launch.xml... + +
    +
    + + + + +
    +
    +
    + mission_planner.launch.xml +
    +
    +
    + package: mission_planner +
    +
    +
    +
    +
    + + mission_planner.launch.xml... + +
    +
    + + + + +
    +
    +
    + goal_pose_visualizer.launch.xml +
    +
    +
    + package: mission_planner +
    +
    +
    +
    +
    + + goal_pose_visualizer.launch.xml... + +
    +
    + + + + + + + + +
    +
    +
    + scenario_selector.launch.xml +
    +
    +
    + package: scenario_selector +
    +
    +
    +
    +
    + + scenario_selector.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + motion_velocity_optimizer.launch.xml +
    +
    +
    + package: motion_velocity_optimizer +
    +
    +
    +
    +
    + + motion_velocity_optimizer.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + lane_driving.launch.xml +
    +
    +
    + package: planning_launch +
    +
    +
    +
    +
    + + lane_driving.launch.xml... + +
    +
    + + + + +
    +
    +
    + parking.launch.py +
    +
    +
    + package: planning_launch +
    +
    +
    +
    +
    + + parking.launch.py... + +
    +
    + + + + +
    + + + + + Viewer does not support full SVG 1.1 + + + +
    \ No newline at end of file diff --git a/sensing_launch/README.md b/sensing_launch/README.md new file mode 100644 index 0000000000..2a6b577a12 --- /dev/null +++ b/sensing_launch/README.md @@ -0,0 +1,49 @@ +# sensing_launch + +## Structure + +![sensing_launch](./sensing_launch.drawio.svg) + +## Package Dependencies + +Please see `` in `package.xml`. + +## Usage + +You can include as follows in `*.launch.xml` to use `sensing.launch.xml`. + +```xml + + + + + + +``` + +## Launch Directory Structure + +This package finds sensor settings of specified sensor model in `launch`. + +```bash +launch/ +├── aip_x1 # Sensor model name +│   ├── camera.launch.xml # Camera +│   ├── gnss.launch.xml # GNSS +│   ├── imu.launch.xml # IMU +│   ├── lidar.launch.xml # LiDAR +│   └── pointcloud_preprocessor.launch.py # for preprocessing pointcloud +... +``` + +## Notes + +This package finds settings with variables. + +ex.) + + + +```xml + +``` diff --git a/sensing_launch/sensing_launch.drawio.svg b/sensing_launch/sensing_launch.drawio.svg new file mode 100644 index 0000000000..4db34b058b --- /dev/null +++ b/sensing_launch/sensing_launch.drawio.svg @@ -0,0 +1,228 @@ + + + + + + + +
    +
    +
    + sensing.launch.xml +
    +
    +
    + + package: sensing_launch + +
    +
    +
    +
    +
    + + sensing.launch.xml... + +
    +
    + + + + +
    +
    +
    + lidar.launch.xml +
    +
    +
    + package: sensing_launch +
    +
    +
    +
    +
    + + lidar.launch.xml... + +
    +
    + + + + + + + + +
    +
    +
    + camera.launch.xml +
    +
    +
    + + package: sensing_launch + +
    +
    +
    +
    +
    + + camera.launch.xml... + +
    +
    + + + + +
    +
    +
    + launch name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + launch name... + +
    +
    + + + + +
    +
    +
    + ex: +
    +
    +
    +
    + + ex: + +
    +
    + + + + +
    +
    +
    + node name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + node name... + +
    +
    + + + + +
    +
    +
    + other name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + other name... + +
    +
    + + + + +
    +
    +
    + imu.launch.xml +
    +
    +
    + + package: sensing_launch + +
    +
    +
    +
    +
    + + imu.launch.xml... + +
    +
    + + + + +
    +
    +
    + imu.launch.xml +
    +
    +
    + + package: sensing_launch + +
    +
    +
    +
    +
    + + imu.launch.xml... + +
    +
    + + + + +
    + + + + + Viewer does not support full SVG 1.1 + + + +
    \ No newline at end of file diff --git a/system_launch/README.md b/system_launch/README.md new file mode 100644 index 0000000000..793c045fc9 --- /dev/null +++ b/system_launch/README.md @@ -0,0 +1,17 @@ +# system_launch + +## Structure + +![system_launch](./system_launch.drawio.svg) + +## Package Dependencies + +Please see `` in `package.xml`. + +## Usage + +```xml + + + +``` diff --git a/system_launch/system_launch.drawio.svg b/system_launch/system_launch.drawio.svg new file mode 100644 index 0000000000..e203f827e5 --- /dev/null +++ b/system_launch/system_launch.drawio.svg @@ -0,0 +1,434 @@ + + + + + + + +
    +
    +
    + system.launch.xml +
    +
    +
    + + package: system_launch + +
    +
    +
    +
    +
    + + system.launch.xml... + +
    +
    + + + + +
    +
    +
    + system_monitor.launch.py +
    +
    +
    + package: system_monitor +
    +
    +
    +
    +
    + + system_monitor.launch.py... + +
    +
    + + + + + + + + + +
    +
    +
    + online +
    +
    +
    +
    + + online + +
    +
    + + + + + +
    +
    +
    + planning_simulation +
    +
    +
    +
    + + planning_simulation + +
    +
    + + + + +
    +
    +
    + $(var run_mode) +
    +
    +
    +
    + + $(var run_mode) + +
    +
    + + + + +
    +
    +
    + launch name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + launch name... + +
    +
    + + + + +
    +
    +
    + ex: +
    +
    +
    +
    + + ex: + +
    +
    + + + + +
    +
    +
    + node name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + node name... + +
    +
    + + + + +
    +
    +
    + other name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + other name... + +
    +
    + + + + +
    +
    +
    + autoware_state_monitor.launch.xml +
    +
    +
    + package: autoware_state_monitor +
    +
    +
    +
    +
    + args: config_file = + + autoware_state_monitor.param.yaml + +
    +
    +
    +
    +
    + + autoware_state_monitor.launch.xml... + +
    +
    + + + + +
    +
    +
    + autoware_state_monitor.launch.xml +
    +
    +
    + package: autoware_state_monitor +
    +
    +
    +
    +
    + args: config_file = + + autoware_state_monitor.planning_simulation.param.yaml + +
    +
    +
    +
    +
    + + autoware_state_monitor.launch.xml... + +
    +
    + + + + + + + +
    +
    +
    + online +
    +
    +
    +
    + + online + +
    +
    + + + + + +
    +
    +
    + planning_simulation +
    +
    +
    +
    + + planning_simulation + +
    +
    + + + + +
    +
    +
    + $(var run_mode) +
    +
    +
    +
    + + $(var run_mode) + +
    +
    + + + + +
    +
    +
    + autoware_error_monitor.launch.xml +
    +
    +
    + package: autoware_error_monitor +
    +
    +
    +
    +
    + args: config_file = + + autoware_error_monitor.param.yaml + +
    +
    +
    +
    +
    + + autoware_error_monitor.launch.xml... + +
    +
    + + + + +
    +
    +
    + autoware_error_monitor.launch.xml +
    +
    +
    + package: autoware_error_monitor +
    +
    +
    +
    +
    + args: config_file = + + autoware_error_monitor.planning_simulation.param.yaml + +
    +
    +
    +
    +
    + + autoware_error_monitor.launch.xml... + +
    +
    + + + + +
    +
    +
    + emergency_handler.launch.xml +
    +
    +
    + package: emergency_handler +
    +
    +
    +
    +
    + + emergency_handler.launch.xml... + +
    +
    + + + + + + +
    +
    +
    + autoware_version +
    +
    +
    + + package: autoware_version + +
    +
    +
    +
    +
    + + autoware_version... + +
    +
    + + +
    + + + + + Viewer does not support full SVG 1.1 + + + +
    \ No newline at end of file diff --git a/vehicle_launch/README.md b/vehicle_launch/README.md new file mode 100644 index 0000000000..de5d447d47 --- /dev/null +++ b/vehicle_launch/README.md @@ -0,0 +1,70 @@ +# vehicle_launch + +## Structure + +![vehicle_launch](./vehicle_launch.drawio.svg) + +## Package Dependencies + +Please see `` in `package.xml`. + +## Usage + +You can include as follows in `*.launch.xml` to use `vehicle.launch.xml`. + +```xml + + + + + + + + + + + + +``` + +## Notes + +This package finds some external packages and settings with variables and package names. + +ex.) + + + +```xml + +``` + + + +```xml + +``` + +## vehicle.xacro + +### Arguments + +| Name | Type | Description | Default | +| ------------- | ------ | ------------------ | ------------------ | +| sensor_model | String | sensor model name | "" | +| vehicle_model | String | vehicle model name | "" | + +### Usage + +You can write as follows in `*.launch.xml`. + +```xml + + + + + + + + +``` diff --git a/vehicle_launch/vehicle_launch.drawio.svg b/vehicle_launch/vehicle_launch.drawio.svg new file mode 100644 index 0000000000..d3165a3a54 --- /dev/null +++ b/vehicle_launch/vehicle_launch.drawio.svg @@ -0,0 +1,442 @@ + + + + + + + +
    +
    +
    + vehicle.launch.xml +
    +
    +
    + + package: vehicle_launch + +
    +
    +
    +
    +
    + + vehicle.launch.xml... + +
    +
    + + + + +
    +
    +
    + vehicle_description.launch.xml +
    +
    +
    + package: vehicle_launch +
    +
    +
    +
    +
    + + vehicle_description.launch.xml... + +
    +
    + + + + + + + + +
    +
    +
    + vehicle_interface.launch.xml +
    +
    +
    + + package: vehicle_launch + +
    +
    +
    +
    +
    + + vehicle_interface.launch.xml... + +
    +
    + + + + +
    +
    +
    + simple_planning_simulator.launch.xml +
    +
    +
    + + package: simple_planning_simulator + +
    +
    +
    +
    +
    + + simple_planning_simulator.launch.xml... + +
    +
    + + + + + +
    +
    +
    + True +
    +
    +
    +
    + + True + +
    +
    + + + + +
    +
    +
    + vehicle_interface.launch.xml +
    +
    +
    + + package: $(var vehicle_model)_description + +
    +
    +
    +
    +
    + + vehicle_interface.launch.xml... + +
    +
    + + + + + +
    +
    +
    + False +
    +
    +
    +
    + + False + +
    +
    + + + + + + +
    +
    +
    + $(var simulation) +
    +
    +
    +
    + + $(var simulation) + +
    +
    + + + + +
    +
    +
    + vehicle.xacro +
    +
    +
    + + package: vehicle_launch + +
    +
    + + +
    +
    +
    +
    +
    + + vehicle.xacro... + +
    +
    + + + + + + +
    +
    +
    + vehicle.xacro +
    +
    + package: $(var vehicle_model)_description +
    +
    +
    +
    + + vehicle.xacro... + +
    +
    + + + + +
    +
    +
    + sensors.xacro +
    +
    +
    + + package: $(var sensor_model)_description + +
    +
    +
    +
    +
    + + sensors.xacro... + +
    +
    + + + + + + + + +
    +
    +
    + launch name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + launch name... + +
    +
    + + + + +
    +
    +
    + ex: +
    +
    +
    +
    + + ex: + +
    +
    + + + + + + +
    +
    +
    + node name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + node name... + +
    +
    + + + + +
    +
    +
    + robot state_publisher +
    +
    +
    + + package: robot_state_publisher + +
    +
    +
    +
    +
    + + robot state_publisher... + +
    +
    + + + + +
    +
    +
    + $(var scenario_simulation) +
    +
    +
    +
    + + $(var scenario_simulation) + +
    +
    + + + + + +
    +
    +
    + False +
    +
    +
    +
    + + False + +
    +
    + + + + +
    +
    +
    + other name +
    +
    +
    + + package: package name + +
    +
    +
    +
    +
    + + other name... + +
    +
    + + + + +
    +
    +
    + vehicle_info.launch.py +
    +
    +
    + + package: vehicle_launch + +
    +
    +
    +
    +
    + + vehicle_info.launch.py... + +
    +
    +
    + + + + + Viewer does not support full SVG 1.1 + + + +
    \ No newline at end of file From 4beedf09c31049cee5a81d959c4ba104e9162da1 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 13 Aug 2021 16:41:45 +0900 Subject: [PATCH 202/851] Fix camera launch invalid type string (#344) Signed-off-by: kosuke55 --- sensing_launch/launch/aip_x1/camera.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing_launch/launch/aip_x1/camera.launch.xml b/sensing_launch/launch/aip_x1/camera.launch.xml index fde088ea77..525b5285fc 100644 --- a/sensing_launch/launch/aip_x1/camera.launch.xml +++ b/sensing_launch/launch/aip_x1/camera.launch.xml @@ -11,7 +11,7 @@ - + From a96b013dd2908d9eaa7ba823e986e01d5dc2e149 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 16 Aug 2021 09:40:49 +0900 Subject: [PATCH 203/851] Change CI docker images to setup-ros-docker (#346) Signed-off-by: Kenji Miyake --- .github/workflows/build_and_test.yml | 2 +- .github/workflows/build_and_test_pr.yml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 008504b60e..2da444379d 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -14,7 +14,7 @@ jobs: branch: - main - develop - container: osrf/ros:galactic-desktop + container: rostooling/setup-ros-docker:ubuntu-focal-ros-galactic-ros-base-latest steps: - name: Checkout repository diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml index 4446020de7..2978174efb 100644 --- a/.github/workflows/build_and_test_pr.yml +++ b/.github/workflows/build_and_test_pr.yml @@ -7,7 +7,7 @@ on: jobs: build-and-test-pr: runs-on: ubuntu-latest - container: osrf/ros:galactic-desktop + container: rostooling/setup-ros-docker:ubuntu-focal-ros-galactic-ros-base-latest steps: - name: Cancel previous runs From 9d7d5a0a5fc5ee6a1c1d43441f297c57b3af73b8 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 16 Aug 2021 10:55:54 +0900 Subject: [PATCH 204/851] Add DEBIAN_FRONTEND=noninteractive to rosdep install (#348) Signed-off-by: Kenji Miyake --- .github/workflows/build_and_test.yml | 2 +- .github/workflows/build_and_test_pr.yml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 2da444379d..16e047639f 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -51,7 +51,7 @@ jobs: vcs import dependency_ws < build_depends.repos apt-get -y update rosdep update - rosdep install -y --from-paths . --ignore-src --rosdistro galactic + DEBIAN_FRONTEND=noninteractive rosdep install -y --from-paths . --ignore-src --rosdistro galactic - name: Build run: | diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml index 2978174efb..4998bcf9e6 100644 --- a/.github/workflows/build_and_test_pr.yml +++ b/.github/workflows/build_and_test_pr.yml @@ -51,7 +51,7 @@ jobs: vcs import dependency_ws < build_depends.repos apt-get -y update rosdep update - rosdep install -y --from-paths . --ignore-src --rosdistro galactic + DEBIAN_FRONTEND=noninteractive rosdep install -y --from-paths . --ignore-src --rosdistro galactic - name: Build if: ${{ steps.list_packages.outputs.package_list != '' }} From 00449ba528a7baac238e647bd29a0cb23dda6009 Mon Sep 17 00:00:00 2001 From: Kosuke Murakami Date: Wed, 18 Aug 2021 13:11:43 +0900 Subject: [PATCH 205/851] Feature/expand footprint launcher (#318) --- control_launch/launch/control.launch.py | 17 +++++++++++++---- .../launch/localization.launch.xml | 6 ------ .../pose_twist_fusion_filter.launch.xml | 4 ++-- 3 files changed, 15 insertions(+), 12 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index e33ff7239f..7b846ca605 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -46,6 +46,10 @@ def launch_setup(context, *args, **kwargs): LaunchConfiguration('vehicle_cmd_gate_param_path').perform(context) with open(vehicle_cmd_gate_param_path, 'r') as f: vehicle_cmd_gate_param = yaml.safe_load(f)['/**']['ros__parameters'] + lane_departure_checker_param_path = \ + LaunchConfiguration('lane_departure_checker_param_path').perform(context) + with open(lane_departure_checker_param_path, 'r') as f: + lane_departure_checker_param = yaml.safe_load(f)['/**']['ros__parameters'] # mpc follower mpc_follower_component = ComposableNode( package='mpc_follower', @@ -138,12 +142,10 @@ def launch_setup(context, *args, **kwargs): ('~/input/route', '/planning/mission_planning/route'), ('~/input/reference_trajectory', '/planning/scenario_planning/trajectory'), ('~/input/predicted_trajectory', '/control/trajectory_follower/predicted_trajectory'), + ('~/input/covariance', '/localization/pose_with_covariance') ], parameters=[ - [ - FindPackageShare('lane_departure_checker'), - '/config/lane_departure_checker.param.yaml' - ] + lane_departure_checker_param ], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') @@ -352,6 +354,13 @@ def add_launch_arg(name: str, default_value=None, description=None): ], 'path to the parameter file of vehicle_cmd_gate' ) + add_launch_arg( + 'lane_departure_checker_param_path', + [ + FindPackageShare('lane_departure_checker'), + '/config/lane_departure_checker.param.yaml' + ] + ) # velocity controller add_launch_arg('control_rate', '30.0', 'control rate') diff --git a/localization_launch/launch/localization.launch.xml b/localization_launch/launch/localization.launch.xml index 116c00fe9e..fe8e93c0c9 100644 --- a/localization_launch/launch/localization.launch.xml +++ b/localization_launch/launch/localization.launch.xml @@ -31,11 +31,5 @@ - - - - - -
    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 6af8ed22ee..07d5bb04dc 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 @@ -12,10 +12,10 @@ - + - + From 902e21d69cb6a894aebf853b1196062a23406ae9 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 26 Aug 2021 12:59:48 +0900 Subject: [PATCH 206/851] fix typo in control.launch.py #363 --- control_launch/control_launch.drawio.svg | 4 ++-- control_launch/launch/control.launch.py | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/control_launch/control_launch.drawio.svg b/control_launch/control_launch.drawio.svg index 82361e0a24..d39b4845b5 100644 --- a/control_launch/control_launch.drawio.svg +++ b/control_launch/control_launch.drawio.svg @@ -94,13 +94,13 @@
    - $(var lateral_control_mode) + $(var lateral_controller_mode)
    - $(var lateral_control_mode) + $(var lateral_controller_mode)
    diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 7b846ca605..ed9e753785 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -292,7 +292,7 @@ def launch_setup(context, *args, **kwargs): composable_node_descriptions=[mpc_follower_component], target_container=container, condition=LaunchConfigurationEquals( - 'lateral_control_mode', 'mpc_follower' + 'lateral_controller_mode', 'mpc_follower' ), ) @@ -300,7 +300,7 @@ def launch_setup(context, *args, **kwargs): composable_node_descriptions=[pure_pursuit_component], target_container=container, condition=LaunchConfigurationEquals( - 'lateral_control_mode', 'pure_pursuit' + 'lateral_controller_mode', 'pure_pursuit' ), ) @@ -320,7 +320,7 @@ def generate_launch_description(): def add_launch_arg(name: str, default_value=None, description=None): launch_arguments.append(DeclareLaunchArgument( name, default_value=default_value, description=description)) - add_launch_arg('lateral_control_mode', 'mpc_follower', + add_launch_arg('lateral_controller_mode', 'mpc_follower', 'lateral control mode: `mpc_follower` or `pure_pursuit`') add_launch_arg( 'mpc_follower_param_path', From 8b90f021a829769f295297e3e9c4ea4ff430f80c Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 26 Aug 2021 13:11:40 +0900 Subject: [PATCH 207/851] Fix description in control launch arg (#364) --- control_launch/launch/control.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index ed9e753785..9a76fc3229 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -321,7 +321,7 @@ def add_launch_arg(name: str, default_value=None, description=None): launch_arguments.append(DeclareLaunchArgument( name, default_value=default_value, description=description)) add_launch_arg('lateral_controller_mode', 'mpc_follower', - 'lateral control mode: `mpc_follower` or `pure_pursuit`') + 'lateral controller mode: `mpc_follower` or `pure_pursuit`') add_launch_arg( 'mpc_follower_param_path', [ From fe3875d5ff888c516647c824f70e820fdb1745e8 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 26 Aug 2021 17:31:20 +0900 Subject: [PATCH 208/851] add view width direction to velodyne_node_container.launch.py etc... (#366) * add arg of view_width and view_direction * delete initial value * add args and params Co-authored-by: autoware-iv-sync-ci[bot] <87871706+autoware-iv-sync-ci[bot]@users.noreply.github.com> --- sensing_launch/launch/velodyne_VLP16.launch.xml | 4 ++++ sensing_launch/launch/velodyne_VLP32C.launch.xml | 4 ++++ sensing_launch/launch/velodyne_VLS128.launch.xml | 4 ++++ sensing_launch/launch/velodyne_node_container.launch.py | 5 ++++- 4 files changed, 16 insertions(+), 1 deletion(-) diff --git a/sensing_launch/launch/velodyne_VLP16.launch.xml b/sensing_launch/launch/velodyne_VLP16.launch.xml index 9382390ffa..61b60884b5 100644 --- a/sensing_launch/launch/velodyne_VLP16.launch.xml +++ b/sensing_launch/launch/velodyne_VLP16.launch.xml @@ -12,6 +12,8 @@ + + @@ -26,6 +28,8 @@ + + diff --git a/sensing_launch/launch/velodyne_VLP32C.launch.xml b/sensing_launch/launch/velodyne_VLP32C.launch.xml index 956ed204fd..208f9da8ad 100644 --- a/sensing_launch/launch/velodyne_VLP32C.launch.xml +++ b/sensing_launch/launch/velodyne_VLP32C.launch.xml @@ -12,6 +12,8 @@ + + @@ -26,6 +28,8 @@ + + diff --git a/sensing_launch/launch/velodyne_VLS128.launch.xml b/sensing_launch/launch/velodyne_VLS128.launch.xml index 79d35df000..0820e641b9 100644 --- a/sensing_launch/launch/velodyne_VLS128.launch.xml +++ b/sensing_launch/launch/velodyne_VLS128.launch.xml @@ -12,6 +12,8 @@ + + @@ -26,6 +28,8 @@ + + diff --git a/sensing_launch/launch/velodyne_node_container.launch.py b/sensing_launch/launch/velodyne_node_container.launch.py index 36007734cc..ae3af1ad00 100644 --- a/sensing_launch/launch/velodyne_node_container.launch.py +++ b/sensing_launch/launch/velodyne_node_container.launch.py @@ -66,7 +66,8 @@ def create_parameter_dict(*args): parameters=[{**create_parameter_dict('calibration', 'min_range', 'max_range', 'num_points_thresholds', 'invalid_intensity', - 'frame_id', 'scan_phase'), + 'frame_id', 'scan_phase', + 'view_direction', 'view_width'), }], remappings=[('velodyne_points', 'pointcloud_raw'), ('velodyne_points_ex', 'pointcloud_raw_ex')], @@ -213,6 +214,8 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg('invalid_intensity') add_launch_arg('frame_id', 'velodyne', 'velodyne frame id') add_launch_arg('gps_time', 'False') + add_launch_arg('view_direction', description='the center of lidar angle') + add_launch_arg('view_width', description='lidar angle: 0~6.28 [rad]') add_launch_arg('input_frame', LaunchConfiguration('base_frame'), 'use for cropbox') add_launch_arg('output_frame', LaunchConfiguration('base_frame'), 'use for cropbox') add_launch_arg('vehicle_param_file', description='path to the file of vehicle info yaml') From d0aae4c11244343b27c2243a86e8368d35d98124 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Fri, 27 Aug 2021 13:51:37 +0900 Subject: [PATCH 209/851] add config directory to perception_launch and data_association_matrix.param.yaml #367 Co-authored-by: autoware-iv-sync-ci[bot] <87871706+autoware-iv-sync-ci[bot]@users.noreply.github.com> --- perception_launch/CMakeLists.txt | 1 + .../data_association_matrix.param.yaml | 52 +++++++++++++++++++ .../tracking/tracking.launch.xml | 1 + 3 files changed, 54 insertions(+) create mode 100644 perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml diff --git a/perception_launch/CMakeLists.txt b/perception_launch/CMakeLists.txt index 4b21dc3b05..ade04cfcd8 100644 --- a/perception_launch/CMakeLists.txt +++ b/perception_launch/CMakeLists.txt @@ -12,4 +12,5 @@ endif() ament_auto_package( INSTALL_TO_SHARE launch + config ) diff --git a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml new file mode 100644 index 0000000000..393bb949d0 --- /dev/null +++ b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml @@ -0,0 +1,52 @@ +/**: + ros__parameters: + can_assign_matrix: + #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL + [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN + 1, 1, 1, 1, 0, 0, 0, 0, #CAR + 1, 1, 1, 1, 0, 0, 0, 0, #TRUCK + 1, 1, 1, 1, 0, 0, 0, 0, #BUS + 0, 0, 0, 0, 1, 1, 1, 0, #BICYCLE + 0, 0, 0, 0, 1, 1, 1, 0, #MOTORBIKE + 0, 0, 0, 0, 1, 1, 1, 0, #PEDESTRIAN + 0, 0, 0, 0, 0, 0, 0, 1] #ANIMAL + max_dist_matrix: + #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL + [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN + 4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #CAR + 4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #TRUCK + 4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #BUS + 3.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #BICYCLE + 3.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #MOTORBIKE + 2.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #PEDESTRIAN + 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0] #ANIMAL + max_area_matrix: + #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL + [10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, #UNKNOWN + 12.10, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #CAR + 19.75, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #TRUCK + 32.40, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #BUS + 2.50, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, 10000.00, #BICYCLE + 3.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, 10000.00, #MOTORBIKE + 2.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00, 10000.00, #PEDESTRIAN + 2.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00] #ANIMAL + min_area_matrix: + #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL + [ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN + 3.600, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #CAR + 6.000, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #TRUCK + 10.000, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #BUS + 0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #BICYCLE + 0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #MOTORBIKE + 0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #PEDESTRIAN + 0.500, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #ANIMAL + max_rad_matrix: # If value is greater than pi, it will be ignored. + #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL + [3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN + 3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #CAR + 3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #TRUCK + 3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #BUS + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #PEDESTRIAN + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #ANIMAL diff --git a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml index 2492a096e9..e34a5bc54d 100644 --- a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml +++ b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml @@ -2,6 +2,7 @@ + From 95cf0e449efa90bdc927ff26e30db401c832211e Mon Sep 17 00:00:00 2001 From: Kazuki Miyahara Date: Fri, 27 Aug 2021 17:17:58 +0900 Subject: [PATCH 210/851] Add spell_check_all action (#369) The manual-trigger action spell-checks all files in the repository. --- .github/workflows/spell_check_all.yml | 35 +++++++++++++++++++++++++++ 1 file changed, 35 insertions(+) create mode 100644 .github/workflows/spell_check_all.yml diff --git a/.github/workflows/spell_check_all.yml b/.github/workflows/spell_check_all.yml new file mode 100644 index 0000000000..7841942f65 --- /dev/null +++ b/.github/workflows/spell_check_all.yml @@ -0,0 +1,35 @@ +name: Check spelling (all files) + +on: + workflow_dispatch: + +jobs: + spellcheck: + runs-on: ubuntu-latest + steps: + - name: Checkout repository + uses: actions/checkout@v2 + + - name: Prepare node + uses: actions/setup-node@v2 + + - name: Install cspell + run: | + npm install cspell + + - name: Retrieve spell check dictionary + run: | + curl --silent --show-error \ + --output .github/workflows/.cspell.json \ + https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json + + - name: Check spelling + run: | + # The cspell-action might not be able to exclude specific files. + # So use cspell package directly instead. + # How to exclude specific files: + # Ex. "**/!(*.osm|*.svg|CHANGELOG.rst)" + ./node_modules/.bin/cspell \ + --config .github/workflows/.cspell.json \ + "**/!(dummy)" \ + 2> /dev/null From a1938848f39a2a0d67ea7d2f0f574fbe59f4e8d7 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Fri, 27 Aug 2021 18:42:17 +0900 Subject: [PATCH 211/851] add ignore patterns (#371) --- .github/workflows/spell_check_all.yml | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/.github/workflows/spell_check_all.yml b/.github/workflows/spell_check_all.yml index 7841942f65..341bc91e9a 100644 --- a/.github/workflows/spell_check_all.yml +++ b/.github/workflows/spell_check_all.yml @@ -2,6 +2,10 @@ name: Check spelling (all files) on: workflow_dispatch: + inputs: + ignore_patterns: + description: "ignore patterns (ex. *.svg|*.osm)" + required: false jobs: spellcheck: @@ -31,5 +35,5 @@ jobs: # Ex. "**/!(*.osm|*.svg|CHANGELOG.rst)" ./node_modules/.bin/cspell \ --config .github/workflows/.cspell.json \ - "**/!(dummy)" \ + "**/!(${{ github.event.inputs.ignore_patterns }})" \ 2> /dev/null From e32dc135a648a4fe9b0d4a56468de481922f0a47 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Fri, 27 Aug 2021 20:10:16 +0900 Subject: [PATCH 212/851] Improve labeler CI (#373) Signed-off-by: Kenji Miyake --- .github/labeler-develop.yml | 4 ++++ .github/labeler-main.yml | 4 ++++ .github/labeler-rc.yml | 4 ++++ .github/labeler.yml | 6 ++---- .github/workflows/labeler.yml | 23 ++++++++++++++++++++--- 5 files changed, 34 insertions(+), 7 deletions(-) create mode 100644 .github/labeler-develop.yml create mode 100644 .github/labeler-main.yml create mode 100644 .github/labeler-rc.yml diff --git a/.github/labeler-develop.yml b/.github/labeler-develop.yml new file mode 100644 index 0000000000..04df147b74 --- /dev/null +++ b/.github/labeler-develop.yml @@ -0,0 +1,4 @@ +develop: + - "**" + - "**/.*" + - ".*/**" diff --git a/.github/labeler-main.yml b/.github/labeler-main.yml new file mode 100644 index 0000000000..5a441060d0 --- /dev/null +++ b/.github/labeler-main.yml @@ -0,0 +1,4 @@ +main: + - "**" + - "**/.*" + - ".*/**" diff --git a/.github/labeler-rc.yml b/.github/labeler-rc.yml new file mode 100644 index 0000000000..1742be2f7b --- /dev/null +++ b/.github/labeler-rc.yml @@ -0,0 +1,4 @@ +rc: + - "**" + - "**/.*" + - ".*/**" diff --git a/.github/labeler.yml b/.github/labeler.yml index c7f4fae4fc..a8d83b209a 100644 --- a/.github/labeler.yml +++ b/.github/labeler.yml @@ -1,4 +1,2 @@ -ROS2: - - "**" -main: - - "**" +CI: + - ".github/**" diff --git a/.github/workflows/labeler.yml b/.github/workflows/labeler.yml index f86110b7b8..6216cbae52 100644 --- a/.github/workflows/labeler.yml +++ b/.github/workflows/labeler.yml @@ -1,12 +1,29 @@ -name: Labeler ROS2 +name: Labeler on: pull_request: + branches: + - main + - develop + - rc/* jobs: - triage: + labeler: runs-on: ubuntu-latest steps: - - uses: actions/labeler@v3 + - name: Run labeler + uses: actions/labeler@v3 with: + configuration-path: .github/labeler.yml + repo-token: "${{ secrets.GITHUB_TOKEN }}" + + - name: Set LABELER_SUFFIX + run: | + branch_name=${GITHUB_BASE_REF#refs/heads/} + echo "LABELER_SUFFIX=${branch_name%/*}" >> $GITHUB_ENV + + - name: Run labeler for branch + uses: actions/labeler@v3 + with: + configuration-path: .github/labeler-${{ env.LABELER_SUFFIX }}.yml repo-token: "${{ secrets.GITHUB_TOKEN }}" From 46c3fdaa1276ee3ca198b7894e8f9983467e0db9 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Tue, 31 Aug 2021 17:12:25 +0900 Subject: [PATCH 213/851] Add autoware api (#376) * Add external api adaptor (#267) * Add external api adaptor * Add api adaptor to logging simulator Signed-off-by: Takagi, Isamu * Add engage status output Signed-off-by: Takagi, Isamu * Add internal api adaptor (#273) Signed-off-by: Takagi, Isamu * Add map hash generator (#319) Signed-off-by: Takagi, Isamu * Add autoware api launch (#326) * Add autoware api launch Signed-off-by: Takagi, Isamu * Apply autoware api launch Signed-off-by: Takagi, Isamu * Add deprecated comment Signed-off-by: Takagi, Isamu * Remove unused parameter (#325) Signed-off-by: Takagi, Isamu * Add api parameter (#341) Signed-off-by: Takagi, Isamu * Add start request API (#321) * Add use start request option Signed-off-by: Takagi, Isamu * Fix lint Signed-off-by: Takagi, Isamu * Feature external cmd selector heartbeat (#356) * Rename external command topic Signed-off-by: Takagi, Isamu * Modify command topic name Signed-off-by: Takagi, Isamu * Fix topic name Signed-off-by: Takagi, Isamu * Rename remote_cmd_converter Signed-off-by: Takagi, Isamu * Remove gate mode from external command Signed-off-by: Takagi, Isamu * Fix latest external command name (#361) Signed-off-by: Takagi, Isamu * Fix merge conflict Signed-off-by: Takagi, Isamu * change external traffic light topic name in behavior velocity planner (#310) * fix topic * change internal topic name Co-authored-by: yabuta --- autoware_api_launch/CMakeLists.txt | 12 +++++ .../launch/autoware_api.launch.xml | 22 ++++++++ autoware_api_launch/package.xml | 24 +++++++++ autoware_launch/launch/autoware.launch.xml | 7 ++- .../launch/logging_simulator.launch.xml | 10 ++-- .../launch/planning_simulator.launch.xml | 7 ++- autoware_launch/package.xml | 4 ++ control_launch/control_launch.drawio.svg | 6 +-- control_launch/launch/control.launch.py | 53 +++++++++++-------- control_launch/launch/control.launch.xml | 35 +++--------- control_launch/package.xml | 2 +- .../launch/util/util.launch.xml | 5 +- map_launch/launch/map.launch.py | 13 +++++ .../behavior_planning.launch.py | 2 +- 14 files changed, 137 insertions(+), 65 deletions(-) create mode 100644 autoware_api_launch/CMakeLists.txt create mode 100644 autoware_api_launch/launch/autoware_api.launch.xml create mode 100644 autoware_api_launch/package.xml diff --git a/autoware_api_launch/CMakeLists.txt b/autoware_api_launch/CMakeLists.txt new file mode 100644 index 0000000000..37c18e108f --- /dev/null +++ b/autoware_api_launch/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 3.5) +project(autoware_api_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_api_launch/launch/autoware_api.launch.xml b/autoware_api_launch/launch/autoware_api.launch.xml new file mode 100644 index 0000000000..8cc3f7efbe --- /dev/null +++ b/autoware_api_launch/launch/autoware_api.launch.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_api_launch/package.xml b/autoware_api_launch/package.xml new file mode 100644 index 0000000000..0e8211d06d --- /dev/null +++ b/autoware_api_launch/package.xml @@ -0,0 +1,24 @@ + + + + + autoware_api_launch + 0.0.0 + The autoware_api_launch package + Takagi, Isamu + Apache License 2.0 + + ament_cmake_auto + + autoware_iv_external_api_adaptor + autoware_iv_internal_api_adaptor + path_distance_calculator + + ament_lint_auto + ament_lint_common + + + ament_cmake + + + diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 2ca581432f..f0163bd35c 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -60,8 +60,11 @@ - - + + + + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 610c932752..762eeea51f 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -43,7 +43,6 @@ - @@ -52,7 +51,6 @@ - @@ -63,14 +61,12 @@ - - @@ -93,6 +89,12 @@ + + + + + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 22a094a20d..b0abe9bfaf 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -63,8 +63,11 @@ - - + + + + + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 6d77abb451..835baed060 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -30,6 +30,10 @@ python-bson python3-bson + + awapi_awiv_adapter + autoware_iv_external_api_adaptor + ament_lint_auto ament_lint_common diff --git a/control_launch/control_launch.drawio.svg b/control_launch/control_launch.drawio.svg index d39b4845b5..f51b6ba126 100644 --- a/control_launch/control_launch.drawio.svg +++ b/control_launch/control_launch.drawio.svg @@ -344,12 +344,12 @@
    - remote_cmd_converter + external_cmd_converter

    - package: remote_cmd_converter + package: external_cmd_converter
    @@ -357,7 +357,7 @@
    - remote_cmd_converter... + external_cmd_converter... diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 9a76fc3229..6ce0102a8c 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -172,20 +172,19 @@ def launch_setup(context, *args, **kwargs): plugin='VehicleCmdGate', name='vehicle_cmd_gate', remappings=[ - ('input/engage', '/autoware/engage'), ('input/system_emergency', '/system/emergency/is_emergency'), - ('input/external_emergency_stop', '/remote/emergency_stop'), ('input/emergency', '/system/emergency/is_emergency'), - ('input/gate_mode', '/remote/gate_mode_cmd'), ('input/steering', '/vehicle/status/steering'), ('input/auto/control_cmd', 'trajectory_follower/control_cmd'), ('input/auto/turn_signal_cmd', '/planning/turn_signal_decider/turn_signal_cmd'), ('input/auto/shift_cmd', '/control/shift_decider/shift_cmd'), - ('input/remote/control_cmd', '/external/external_cmd_selector/control_cmd'), - ('input/remote/turn_signal_cmd', '/external/external_cmd_selector/turn_signal_cmd'), - ('input/remote/shift_cmd', '/external/external_cmd_selector/shift_cmd'), + ('input/external/control_cmd', '/external/selected/control_cmd'), + ('input/external/turn_signal_cmd', '/external/selected/turn_signal_cmd'), + ('input/external/shift_cmd', '/external/selected/shift_cmd'), + ('input/external_emergency_stop', '/external/selected/heartbeat'), + ('input/gate_mode', '/control/gate_mode_cmd'), ('input/emergency/control_cmd', '/system/emergency/control_cmd'), ('input/emergency/turn_signal_cmd', '/system/emergency/turn_signal_cmd'), @@ -196,7 +195,13 @@ def launch_setup(context, *args, **kwargs): ('output/shift_cmd', '/control/shift_cmd'), ('output/turn_signal_cmd', '/control/turn_signal_cmd'), ('output/gate_mode', '/control/current_gate_mode'), + ('output/engage', '/api/autoware/get/engage'), + + ('~/service/engage', '/api/autoware/set/engage'), + ('~/service/external_emergency', '/api/autoware/set/emergency'), + # TODO(Takagi, Isamu): deprecated + ('input/engage', '/autoware/engage'), ('~/service/external_emergency_stop', '~/external_emergency_stop'), ('~/service/clear_external_emergency_stop', '~/clear_external_emergency_stop'), ], @@ -205,6 +210,7 @@ def launch_setup(context, *args, **kwargs): { 'use_emergency_handling': LaunchConfiguration('use_emergency_handling'), 'use_external_emergency_stop': LaunchConfiguration('use_external_emergency_stop'), + 'use_start_request': LaunchConfiguration('use_start_request'), } ], extra_arguments=[{ @@ -218,18 +224,20 @@ def launch_setup(context, *args, **kwargs): plugin='ExternalCmdSelector', name='external_cmd_selector', remappings=[ + ('~/service/select_external_command', '~/select_external_command'), ('~/input/local/control_cmd', '/external/local/control_cmd'), ('~/input/local/shift_cmd', '/external/local/shift_cmd'), ('~/input/local/turn_signal_cmd', '/external/local/turn_signal_cmd'), + ('~/input/local/heartbeat', '/external/local/heartbeat'), ('~/input/remote/control_cmd', '/external/remote/control_cmd'), ('~/input/remote/shift_cmd', '/external/remote/shift_cmd'), ('~/input/remote/turn_signal_cmd', '/external/remote/turn_signal_cmd'), + ('~/input/remote/heartbeat', '/external/remote/heartbeat'), + ('~/output/control_cmd', '/external/selected/external_control_cmd'), + ('~/output/shift_cmd', '/external/selected/shift_cmd'), + ('~/output/turn_signal_cmd', '/external/selected/turn_signal_cmd'), + ('~/output/heartbeat', '/external/selected/heartbeat'), ('~/output/current_selector_mode', '~/current_selector_mode'), - ('~/output/external_control_cmd', - '/external/external_cmd_selector/external_control_cmd'), - ('~/output/shift_cmd', '/external/external_cmd_selector/shift_cmd'), - ('~/output/turn_signal_cmd', '/external/external_cmd_selector/turn_signal_cmd'), - ('~/service/select_external_command', '~/select_external_command'), ], parameters=[ { @@ -241,19 +249,19 @@ def launch_setup(context, *args, **kwargs): }], ) - # remote cmd converter - remote_cmd_converter_component = ComposableNode( - package='remote_cmd_converter', - plugin='RemoteCmdConverter', - name='remote_cmd_converter', + # external cmd converter + external_cmd_converter_component = ComposableNode( + package='external_cmd_converter', + plugin='external_cmd_converter::ExternalCmdConverterNode', + name='external_cmd_converter', remappings=[ - ('in/external_control_cmd', '/external/external_cmd_selector/external_control_cmd'), - ('in/shift_cmd', '/external/external_cmd_selector/shift_cmd'), + ('in/external_control_cmd', '/external/selected/external_control_cmd'), + ('in/shift_cmd', '/external/selected/shift_cmd'), ('in/emergency_stop', '/remote/emergency_stop'), ('in/current_gate_mode', '/control/current_gate_mode'), ('in/twist', '/localization/twist'), - ('out/control_cmd', '/external/external_cmd_selector/control_cmd'), - ('out/latest_remote_control_cmd', '/remote/latest_remote_control_cmd'), + ('out/control_cmd', '/external/selected/control_cmd'), + ('out/latest_external_control_cmd', '/external/selected/latest_external_control_cmd'), ], parameters=[ { @@ -283,7 +291,7 @@ def launch_setup(context, *args, **kwargs): lane_departure_component, shift_decider_component, vehicle_cmd_gate_component, - remote_cmd_converter_component, + external_cmd_converter_component, external_cmd_selector_component, ], ) @@ -372,9 +380,10 @@ def add_launch_arg(name: str, default_value=None, description=None): # vehicle cmd gate add_launch_arg('use_emergency_handling', 'false', 'use emergency handling') add_launch_arg('use_external_emergency_stop', 'true', 'use external emergency stop') + add_launch_arg('use_start_request', 'false', 'use start request service') # external cmd selector - add_launch_arg('initial_selector_mode', '1', '0: Local, 1: Remote') + add_launch_arg('initial_selector_mode', 'remote', 'local or remote') # remote cmd converter add_launch_arg( diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index 940fc887a4..b464ce390a 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -58,43 +58,24 @@ - - - - - - - - - - - - - - - - - - - - - + - + + - - - - - + + + + + diff --git a/control_launch/package.xml b/control_launch/package.xml index c668eb210e..fd1003d974 100644 --- a/control_launch/package.xml +++ b/control_launch/package.xml @@ -14,7 +14,7 @@ latlon_muxer mpc_follower pure_pursuit - remote_cmd_converter + external_cmd_converter shift_decider vehicle_cmd_gate velocity_controller diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 8bed2b2304..5ea9bfce95 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -17,10 +17,9 @@ - - - + + diff --git a/map_launch/launch/map.launch.py b/map_launch/launch/map.launch.py index 925ac2fcf0..804e118297 100644 --- a/map_launch/launch/map.launch.py +++ b/map_launch/launch/map.launch.py @@ -20,11 +20,23 @@ from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import Node from launch_ros.actions import PushRosNamespace from launch_ros.descriptions import ComposableNode def generate_launch_description(): + map_hash_generator = Node( + package='map_loader', + executable='map_hash_generator', + name='map_hash_generator', + parameters=[ + { + 'lanelet2_map_path': LaunchConfiguration('lanelet2_map_path'), + } + ], + ) + lanelet2_map_loader = ComposableNode( package='map_loader', plugin='Lanelet2MapLoaderNode', @@ -122,5 +134,6 @@ def add_launch_arg(name: str, default_value=None, description=None): GroupAction([ PushRosNamespace('map'), container, + map_hash_generator, ]) ]) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 677230e71f..6fd1cb9076 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -162,7 +162,7 @@ def generate_launch_description(): ('~/input/traffic_light_states', '/perception/traffic_light_recognition/traffic_light_states'), ('~/input/external_traffic_light_states', - '/awapi/traffic_light/put/traffic_light_status'), + '/external/traffic_light_recognition/traffic_light_states'), ('~/output/path', 'path'), ('~/output/stop_reasons', '/planning/scenario_planning/status/stop_reasons'), From c2204fdf4710a32f3e99032db294d8ad7b14934a Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 1 Sep 2021 22:12:36 +0900 Subject: [PATCH 214/851] Bump streetsidesoftware/cspell-action from 1.2.5 to 1.3.1 (#382) Bumps [streetsidesoftware/cspell-action](https://github.com/streetsidesoftware/cspell-action) from 1.2.5 to 1.3.1. - [Release notes](https://github.com/streetsidesoftware/cspell-action/releases) - [Changelog](https://github.com/streetsidesoftware/cspell-action/blob/main/CHANGELOG.md) - [Commits](https://github.com/streetsidesoftware/cspell-action/compare/v1.2.5...v1.3.1) --- updated-dependencies: - dependency-name: streetsidesoftware/cspell-action dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/spell_check_pr.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/spell_check_pr.yml b/.github/workflows/spell_check_pr.yml index 0ace0086f8..93bf74ac4c 100644 --- a/.github/workflows/spell_check_pr.yml +++ b/.github/workflows/spell_check_pr.yml @@ -16,6 +16,6 @@ jobs: --output .github/workflows/.cspell.json \ https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json - - uses: streetsidesoftware/cspell-action@v1.2.5 + - uses: streetsidesoftware/cspell-action@v1.3.1 with: config: ".github/workflows/.cspell.json" From 4214390866020e746b6bcb13787a76a819d8799a Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 3 Sep 2021 08:42:38 +0900 Subject: [PATCH 215/851] added stop filter launch in localization_launch (#270) --- .../pose_twist_fusion_filter.launch.xml | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) 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 07d5bb04dc..ba2ee548d8 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 @@ -15,7 +15,7 @@ - + @@ -23,4 +23,11 @@ + + + + + + + From 5858dc91bc62d0096b5d2d1d9187074096c22186 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 3 Sep 2021 10:32:59 +0900 Subject: [PATCH 216/851] Merge pull request #359 from tier4/feature/add_plannig_error_monitor (#365) --- planning_launch/launch/planning.launch.xml | 7 +++++++ .../planning_error_monitor.launch.xml | 8 ++++++++ 2 files changed, 15 insertions(+) create mode 100644 planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml diff --git a/planning_launch/launch/planning.launch.xml b/planning_launch/launch/planning.launch.xml index 003af6fca8..3f33650f47 100644 --- a/planning_launch/launch/planning.launch.xml +++ b/planning_launch/launch/planning.launch.xml @@ -15,5 +15,12 @@ + + + + + + + diff --git a/planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml b/planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml new file mode 100644 index 0000000000..0555cbf965 --- /dev/null +++ b/planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml @@ -0,0 +1,8 @@ + + + + + + + + From 1a0b6bc2818e3c82ea4a16d836bf9b716a57c27d Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Fri, 3 Sep 2021 16:09:34 +0900 Subject: [PATCH 217/851] Feature/add virtual traffic light planner (#317) --- autoware_launch/rviz/autoware.rviz | 18 ++++++++++++++++++ .../behavior_planning.launch.py | 16 +++++++++++++++- 2 files changed, 33 insertions(+), 1 deletion(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 4641c2a876..2e97c3d219 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -974,6 +974,24 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/traffic_light Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualTrafficLight + Namespaces: + end_lines: false + instrument_center: false + instrument_id: false + start_line: false + stop_factor_text: true + stop_line: false + stop_virtual_wall: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/virtual_traffic_light + Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true Name: StopLine diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 6fd1cb9076..c88a203caa 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -148,6 +148,14 @@ def generate_launch_description(): with open(traffic_light_param_path, 'r') as f: traffic_light_param = yaml.safe_load(f)['/**']['ros__parameters'] + virtual_traffic_light_param_path = os.path.join( + get_package_share_directory('behavior_velocity_planner'), + 'config', + 'virtual_traffic_light.param.yaml', + ) + with open(virtual_traffic_light_param_path, 'r') as f: + virtual_traffic_light_param = yaml.safe_load(f)['/**']['ros__parameters'] + behavior_velocity_planner_component = ComposableNode( package='behavior_velocity_planner', plugin='behavior_velocity_planner::BehaviorVelocityPlannerNode', @@ -163,9 +171,13 @@ def generate_launch_description(): '/perception/traffic_light_recognition/traffic_light_states'), ('~/input/external_traffic_light_states', '/external/traffic_light_recognition/traffic_light_states'), + ('~/input/virtual_traffic_light_states', + '/awapi/tmp/virtual_traffic_light_states'), ('~/output/path', 'path'), ('~/output/stop_reasons', '/planning/scenario_planning/status/stop_reasons'), + ('~/output/infrastructure_commands', + '/planning/scenario_planning/status/infrastructure_commands'), ('~/output/traffic_light_state', 'debug/traffic_light_state'), ], parameters=[ @@ -176,6 +188,7 @@ def generate_launch_description(): 'launch_intersection': True, 'launch_blind_spot': True, 'launch_detection_area': True, + 'launch_virtual_traffic_light': True, 'forward_path_length': 1000.0, 'backward_path_length': 5.0, 'max_accel': -2.8, @@ -186,7 +199,8 @@ def generate_launch_description(): detection_area_param, intersection_param, stop_line_param, - traffic_light_param + traffic_light_param, + virtual_traffic_light_param, ], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') From 2d149cad590fb1a23a216ee849818045b0f1bb91 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Fri, 3 Sep 2021 19:24:05 +0900 Subject: [PATCH 218/851] Move autoware api launch files (#387) --- .../launch/autoware_api.launch.xml | 6 +-- .../include/external_api_adaptor.launch.py | 52 +++++++++++++++++++ .../include/internal_api_adaptor.launch.py | 51 ++++++++++++++++++ .../include/internal_api_relay.launch.xml | 26 ++++++++++ autoware_api_launch/package.xml | 2 + autoware_launch/package.xml | 5 +- 6 files changed, 135 insertions(+), 7 deletions(-) create mode 100644 autoware_api_launch/launch/include/external_api_adaptor.launch.py create mode 100644 autoware_api_launch/launch/include/internal_api_adaptor.launch.py create mode 100644 autoware_api_launch/launch/include/internal_api_relay.launch.xml diff --git a/autoware_api_launch/launch/autoware_api.launch.xml b/autoware_api_launch/launch/autoware_api.launch.xml index 8cc3f7efbe..9e1baf93e5 100644 --- a/autoware_api_launch/launch/autoware_api.launch.xml +++ b/autoware_api_launch/launch/autoware_api.launch.xml @@ -8,9 +8,9 @@ - - - + + + diff --git a/autoware_api_launch/launch/include/external_api_adaptor.launch.py b/autoware_api_launch/launch/include/external_api_adaptor.launch.py new file mode 100644 index 0000000000..357b35f412 --- /dev/null +++ b/autoware_api_launch/launch/include/external_api_adaptor.launch.py @@ -0,0 +1,52 @@ +# Copyright 2021 Tier IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import launch +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + + +def _create_api_node(node_name, class_name, **kwargs): + return ComposableNode( + namespace='external', + name=node_name, + package='autoware_iv_external_api_adaptor', + plugin='external_api::' + class_name, + **kwargs + ) + + +def generate_launch_description(): + components = [ + _create_api_node('diagnostics', 'Diagnostics'), + _create_api_node('door', 'Door'), + _create_api_node('emergency', 'Emergency'), + _create_api_node('engage', 'Engage'), + _create_api_node('initial_pose', 'InitialPose'), + _create_api_node('map', 'Map'), + _create_api_node('operator', 'Operator'), + _create_api_node('route', 'Route'), + _create_api_node('service', 'Service'), + _create_api_node('velocity', 'Velocity'), + _create_api_node('version', 'Version'), + ] + container = ComposableNodeContainer( + namespace='external', + name='autoware_iv_adaptor', + package='rclcpp_components', + executable='component_container_mt', + composable_node_descriptions=components, + output='screen', + ) + return launch.LaunchDescription([container]) diff --git a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py new file mode 100644 index 0000000000..80fa57932c --- /dev/null +++ b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py @@ -0,0 +1,51 @@ +# Copyright 2021 Tier IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import launch +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + + +def _create_api_node(node_name, class_name, **kwargs): + return ComposableNode( + namespace='internal', + name=node_name, + package='autoware_iv_internal_api_adaptor', + plugin='internal_api::' + class_name, + **kwargs + ) + + +def generate_launch_description(): + param_initial_pose = { + 'init_simulator_pose': LaunchConfiguration('init_simulator_pose'), + 'init_localization_pose': LaunchConfiguration('init_localization_pose'), + } + components = [ + _create_api_node('initial_pose', 'InitialPose', parameters=[param_initial_pose]), + _create_api_node('operator', 'Operator'), + _create_api_node('route', 'Route'), + _create_api_node('start', 'Start'), + _create_api_node('velocity', 'Velocity'), + ] + container = ComposableNodeContainer( + namespace='internal', + name='autoware_iv_adaptor', + package='rclcpp_components', + executable='component_container_mt', + composable_node_descriptions=components, + output='screen', + ) + return launch.LaunchDescription([container]) diff --git a/autoware_api_launch/launch/include/internal_api_relay.launch.xml b/autoware_api_launch/launch/include/internal_api_relay.launch.xml new file mode 100644 index 0000000000..ab4df03907 --- /dev/null +++ b/autoware_api_launch/launch/include/internal_api_relay.launch.xml @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_api_launch/package.xml b/autoware_api_launch/package.xml index 0e8211d06d..f8698287b9 100644 --- a/autoware_api_launch/package.xml +++ b/autoware_api_launch/package.xml @@ -10,9 +10,11 @@ ament_cmake_auto + awapi_awiv_adapter autoware_iv_external_api_adaptor autoware_iv_internal_api_adaptor path_distance_calculator + topic_tools ament_lint_auto ament_lint_common diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 835baed060..8a744017b4 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -10,6 +10,7 @@ ament_cmake_auto + autoware_api_launch control_launch localization_launch map_launch @@ -30,10 +31,6 @@ python-bson python3-bson - - awapi_awiv_adapter - autoware_iv_external_api_adaptor - ament_lint_auto ament_lint_common From 7fc300fa5ff411a03c2f49d2c75e38f87aabbec1 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Mon, 6 Sep 2021 13:27:02 +0900 Subject: [PATCH 219/851] Move start request API (#391) --- .../launch/include/external_api_adaptor.launch.py | 1 + .../launch/include/internal_api_adaptor.launch.py | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_api_launch/launch/include/external_api_adaptor.launch.py b/autoware_api_launch/launch/include/external_api_adaptor.launch.py index 357b35f412..6eca7b7553 100644 --- a/autoware_api_launch/launch/include/external_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/external_api_adaptor.launch.py @@ -38,6 +38,7 @@ def generate_launch_description(): _create_api_node('operator', 'Operator'), _create_api_node('route', 'Route'), _create_api_node('service', 'Service'), + _create_api_node('start', 'Start'), _create_api_node('velocity', 'Velocity'), _create_api_node('version', 'Version'), ] diff --git a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py index 80fa57932c..f4e779b584 100644 --- a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py @@ -37,7 +37,6 @@ def generate_launch_description(): _create_api_node('initial_pose', 'InitialPose', parameters=[param_initial_pose]), _create_api_node('operator', 'Operator'), _create_api_node('route', 'Route'), - _create_api_node('start', 'Start'), _create_api_node('velocity', 'Velocity'), ] container = ComposableNodeContainer( From e22bf9338245f3d863fe7bc6da841aa6d0d21231 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Mon, 6 Sep 2021 18:56:19 +0900 Subject: [PATCH 220/851] Fix misspell in rviz config (#392) Signed-off-by: Takagi, Isamu --- 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 2e97c3d219..a49557207d 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1043,7 +1043,7 @@ Visualization Manager: - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true - Name: LaneChangeCanditate + Name: LaneChangeCandidate Topic: Depth: 5 Durability Policy: Volatile From 97f4f39ec622bea757c0e2e81664285209fb351c Mon Sep 17 00:00:00 2001 From: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Date: Tue, 7 Sep 2021 13:48:50 +0900 Subject: [PATCH 221/851] add sync-rc workflow (#393) --- .github/workflows/sync-rc.yml | 72 +++++++++++++++++++++++++++++++++++ 1 file changed, 72 insertions(+) create mode 100644 .github/workflows/sync-rc.yml diff --git a/.github/workflows/sync-rc.yml b/.github/workflows/sync-rc.yml new file mode 100644 index 0000000000..26645d10d8 --- /dev/null +++ b/.github/workflows/sync-rc.yml @@ -0,0 +1,72 @@ +name: sync rc + +on: + pull_request: + branches: + - "rc/*" + types: + - closed + workflow_dispatch: + +env: + BASE_BRANCH: main + SYNC_BRANCH: sync-rc + +jobs: + sync-rc: + runs-on: ubuntu-20.04 + + steps: + - name: Checkout repository + uses: actions/checkout@v2 + with: + ref: ${{ env.BASE_BRANCH }} + fetch-depth: 0 + + - name: Generate token + uses: tibdex/github-app-token@v1 + id: generate-token + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.APP_PRIVATE_KEY }} + + - name: Set SYNC_TARGET_BRANCH + run: | + echo "SYNC_TARGET_BRANCH=${{ github.head_ref }}" >> $GITHUB_ENV + + # To keep the base branch in "create-pull-request", checkout with "BASE_BRANCH" and reset to "SYNC_TARGET_BRANCH" + - name: Reset to sync target branch + run: | + git reset --hard origin/${{ env.SYNC_TARGET_BRANCH }} + + - name: Create PR + id: create_pr + uses: peter-evans/create-pull-request@v3 + with: + token: ${{ steps.generate-token.outputs.token }} + commit-message: sync rc + committer: GitHub + author: GitHub + signoff: false + base: ${{ env.BASE_BRANCH }} + branch: ${{ env.SYNC_BRANCH }} + delete-branch: true + title: sync rc + body: | + sync rc + labels: | + sync-rc + draft: false + + - name: Check outputs + run: | + echo "Pull Request Number - ${{ steps.create_pr.outputs.pull-request-number }}" + echo "Pull Request URL - ${{ steps.create_pr.outputs.pull-request-url }}" + + - name: Enable Auto-merge + if: steps.create_pr.outputs.pull-request-operation == 'created' + uses: peter-evans/enable-pull-request-automerge@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + pull-request-number: ${{ steps.create_pr.outputs.pull-request-number }} + merge-method: merge From 2a66503c7a67ff69c426e4787cc67a926268ed92 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Tue, 7 Sep 2021 16:29:25 +0900 Subject: [PATCH 222/851] Move launch file of external_cmd_selector (#386) * Move launch file of external_cmd_selector Signed-off-by: Takagi, Isamu * Add utility function to include launch.py Signed-off-by: Takagi, Isamu * Add missing parameter Signed-off-by: Takagi, Isamu * Fix external command api name Signed-off-by: Takagi, Isamu * move common parameters Signed-off-by: Takagi, Isamu * Fix format Signed-off-by: Takagi, Isamu --- control_launch/launch/control.launch.py | 39 +++++++----------------- control_launch/launch/control.launch.xml | 8 ----- 2 files changed, 11 insertions(+), 36 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 6ce0102a8c..64073da1ba 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -15,11 +15,13 @@ import launch from launch.actions import DeclareLaunchArgument from launch.actions import GroupAction +from launch.actions import IncludeLaunchDescription from launch.actions import OpaqueFunction from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition from launch.conditions import LaunchConfigurationEquals from launch.conditions import UnlessCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer from launch_ros.actions import LoadComposableNodes @@ -219,34 +221,15 @@ def launch_setup(context, *args, **kwargs): ) # external cmd selector - external_cmd_selector_component = ComposableNode( - package='external_cmd_selector', - plugin='ExternalCmdSelector', - name='external_cmd_selector', - remappings=[ - ('~/service/select_external_command', '~/select_external_command'), - ('~/input/local/control_cmd', '/external/local/control_cmd'), - ('~/input/local/shift_cmd', '/external/local/shift_cmd'), - ('~/input/local/turn_signal_cmd', '/external/local/turn_signal_cmd'), - ('~/input/local/heartbeat', '/external/local/heartbeat'), - ('~/input/remote/control_cmd', '/external/remote/control_cmd'), - ('~/input/remote/shift_cmd', '/external/remote/shift_cmd'), - ('~/input/remote/turn_signal_cmd', '/external/remote/turn_signal_cmd'), - ('~/input/remote/heartbeat', '/external/remote/heartbeat'), - ('~/output/control_cmd', '/external/selected/external_control_cmd'), - ('~/output/shift_cmd', '/external/selected/shift_cmd'), - ('~/output/turn_signal_cmd', '/external/selected/turn_signal_cmd'), - ('~/output/heartbeat', '/external/selected/heartbeat'), - ('~/output/current_selector_mode', '~/current_selector_mode'), - ], - parameters=[ - { - 'initial_selector_mode': LaunchConfiguration('initial_selector_mode'), - } + external_cmd_selector_loader = IncludeLaunchDescription( + PythonLaunchDescriptionSource([ + FindPackageShare('external_cmd_selector'), '/launch/external_cmd_selector.launch.py' + ]), + launch_arguments=[ + ('use_intra_process', LaunchConfiguration('use_intra_process')), + ('target_container', '/control/control_container'), + ('initial_selector_mode', 'remote'), ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], ) # external cmd converter @@ -292,7 +275,6 @@ def launch_setup(context, *args, **kwargs): shift_decider_component, vehicle_cmd_gate_component, external_cmd_converter_component, - external_cmd_selector_component, ], ) @@ -315,6 +297,7 @@ def launch_setup(context, *args, **kwargs): group = GroupAction([ PushRosNamespace('control'), container, + external_cmd_selector_loader, mpc_follower_loader, pure_pursuit_loader ]) diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index b464ce390a..aba4dc6b02 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -61,14 +61,6 @@ - - - - - - - - From b3b834f0332763d2828bd3ce51d469846ad95f03 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Fri, 10 Sep 2021 13:14:29 +0900 Subject: [PATCH 223/851] Use EmergencyState instead of deprecated EmergencyMode (#390) * Use EmergencyState instead of deprecated EmergencyMode Signed-off-by: Kenji Miyake * Update control.launch.py --- control_launch/launch/control.launch.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 64073da1ba..40110f64c3 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -174,8 +174,7 @@ def launch_setup(context, *args, **kwargs): plugin='VehicleCmdGate', name='vehicle_cmd_gate', remappings=[ - ('input/system_emergency', '/system/emergency/is_emergency'), - ('input/emergency', '/system/emergency/is_emergency'), + ('input/emergency_state', '/system/emergency/emergency_state'), ('input/steering', '/vehicle/status/steering'), ('input/auto/control_cmd', 'trajectory_follower/control_cmd'), @@ -185,7 +184,7 @@ def launch_setup(context, *args, **kwargs): ('input/external/control_cmd', '/external/selected/control_cmd'), ('input/external/turn_signal_cmd', '/external/selected/turn_signal_cmd'), ('input/external/shift_cmd', '/external/selected/shift_cmd'), - ('input/external_emergency_stop', '/external/selected/heartbeat'), + ('input/external_emergency_stop_heartbeat', '/external/selected/heartbeat'), ('input/gate_mode', '/control/gate_mode_cmd'), ('input/emergency/control_cmd', '/system/emergency/control_cmd'), From dcd9a574ea5d19e84ff8e7b0b2b21a599dfeb825 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Fri, 10 Sep 2021 13:29:29 +0900 Subject: [PATCH 224/851] Add selected external command API (#397) --- .../include/internal_api_relay.launch.xml | 2 +- control_launch/launch/control.launch.py | 59 +++---------------- control_launch/launch/control.launch.xml | 3 - 3 files changed, 10 insertions(+), 54 deletions(-) diff --git a/autoware_api_launch/launch/include/internal_api_relay.launch.xml b/autoware_api_launch/launch/include/internal_api_relay.launch.xml index ab4df03907..bb3bd72a5b 100644 --- a/autoware_api_launch/launch/include/internal_api_relay.launch.xml +++ b/autoware_api_launch/launch/include/internal_api_relay.launch.xml @@ -17,7 +17,7 @@ - + diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 40110f64c3..088885eccd 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -232,33 +232,14 @@ def launch_setup(context, *args, **kwargs): ) # external cmd converter - external_cmd_converter_component = ComposableNode( - package='external_cmd_converter', - plugin='external_cmd_converter::ExternalCmdConverterNode', - name='external_cmd_converter', - remappings=[ - ('in/external_control_cmd', '/external/selected/external_control_cmd'), - ('in/shift_cmd', '/external/selected/shift_cmd'), - ('in/emergency_stop', '/remote/emergency_stop'), - ('in/current_gate_mode', '/control/current_gate_mode'), - ('in/twist', '/localization/twist'), - ('out/control_cmd', '/external/selected/control_cmd'), - ('out/latest_external_control_cmd', '/external/selected/latest_external_control_cmd'), - ], - parameters=[ - { - 'csv_path_accel_map': LaunchConfiguration('csv_path_accel_map'), - 'csv_path_brake_map': LaunchConfiguration('csv_path_brake_map'), - - 'ref_vel_gain': LaunchConfiguration('ref_vel_gain'), - 'wait_for_first_topic': LaunchConfiguration('wait_for_first_topic'), - 'control_command_timeout': LaunchConfiguration('control_command_timeout'), - 'emergency_stop_timeout': LaunchConfiguration('emergency_stop_timeout'), - } + external_cmd_converter_loader = IncludeLaunchDescription( + PythonLaunchDescriptionSource([ + FindPackageShare('external_cmd_converter'), '/launch/external_cmd_converter.launch.py' + ]), + launch_arguments=[ + ('use_intra_process', LaunchConfiguration('use_intra_process')), + ('target_container', '/control/control_container'), ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], ) # set container to run all required components in the same process @@ -273,7 +254,6 @@ def launch_setup(context, *args, **kwargs): lane_departure_component, shift_decider_component, vehicle_cmd_gate_component, - external_cmd_converter_component, ], ) @@ -297,6 +277,7 @@ def launch_setup(context, *args, **kwargs): PushRosNamespace('control'), container, external_cmd_selector_loader, + external_cmd_converter_loader, mpc_follower_loader, pure_pursuit_loader ]) @@ -367,29 +348,7 @@ def add_launch_arg(name: str, default_value=None, description=None): # external cmd selector add_launch_arg('initial_selector_mode', 'remote', 'local or remote') - # remote cmd converter - add_launch_arg( - 'csv_path_accel_map', - [ - FindPackageShare('raw_vehicle_cmd_converter'), - '/data/default/accel_map.csv' - ], - 'csv file path for accel map' - ) - add_launch_arg( - 'csv_path_brake_map', - [ - FindPackageShare('raw_vehicle_cmd_converter'), - '/data/default/brake_map.csv' - ], - 'csv file path for brake map' - ) - add_launch_arg('ref_vel_gain', '3.0', 'gain for remote command accel') - add_launch_arg('wait_for_first_topic', 'true', - 'disable topic disruption detection until subscribing first topics') - add_launch_arg('control_command_timeout', '1.0', 'remote control command timeout') - add_launch_arg('emergency_stop_timeout', '3.0', 'emergency stop timeout for remote heartbeat') - + # component add_launch_arg('use_intra_process', 'false', 'use ROS2 component container communication') add_launch_arg('use_multithread', 'false', 'use multithread') set_container_executable = SetLaunchConfiguration( diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index aba4dc6b02..b8115d42a0 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -65,9 +65,6 @@ - - - From 4b4db9efc69ddfd2b5df41b63f60f0531eb3eb90 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Sun, 12 Sep 2021 23:50:38 +0900 Subject: [PATCH 225/851] Fix sync-rc.yml (#402) Signed-off-by: Kenji Miyake --- .github/workflows/sync-rc.yml | 33 +++++++++++++++++++++++++++++---- 1 file changed, 29 insertions(+), 4 deletions(-) diff --git a/.github/workflows/sync-rc.yml b/.github/workflows/sync-rc.yml index 26645d10d8..f3a6a35084 100644 --- a/.github/workflows/sync-rc.yml +++ b/.github/workflows/sync-rc.yml @@ -7,10 +7,13 @@ on: types: - closed workflow_dispatch: + inputs: + rc_branch: + description: "Target RC branch(e.g. rc/v1.0.0)" + required: true env: BASE_BRANCH: main - SYNC_BRANCH: sync-rc jobs: sync-rc: @@ -30,15 +33,37 @@ jobs: app_id: ${{ secrets.APP_ID }} private_key: ${{ secrets.APP_PRIVATE_KEY }} - - name: Set SYNC_TARGET_BRANCH + - name: Set SYNC_TARGET_BRANCH for pull_request event + if: github.event_name == 'pull_request' run: | - echo "SYNC_TARGET_BRANCH=${{ github.head_ref }}" >> $GITHUB_ENV + echo "SYNC_TARGET_BRANCH=${{ github.base_ref }}" >> $GITHUB_ENV + + - name: Set SYNC_TARGET_BRANCH for workflow_dispatch event + if: github.event_name == 'workflow_dispatch' + run: | + echo "SYNC_TARGET_BRANCH=${{ github.event.inputs.rc_branch }}" >> $GITHUB_ENV + + - name: Set SYNC_BRANCH + run: | + echo ${SYNC_TARGET_BRANCH} | grep -e "^rc/v.*" + echo "SYNC_BRANCH=sync-rc/${SYNC_TARGET_BRANCH#refs/heads/}" >> $GITHUB_ENV # To keep the base branch in "create-pull-request", checkout with "BASE_BRANCH" and reset to "SYNC_TARGET_BRANCH" - name: Reset to sync target branch run: | git reset --hard origin/${{ env.SYNC_TARGET_BRANCH }} + - name: Set git config + run: | + git config --local user.email "actions@example.com" + git config --local user.name "Github Actions" + + - name: Rebase on the base branch + run: | + for commit in $(git rev-list --left-only origin/${{ env.BASE_BRANCH }}...HEAD | tac); do + git rebase $commit || git rebase --abort + done + - name: Create PR id: create_pr uses: peter-evans/create-pull-request@v3 @@ -69,4 +94,4 @@ jobs: with: token: ${{ steps.generate-token.outputs.token }} pull-request-number: ${{ steps.create_pr.outputs.pull-request-number }} - merge-method: merge + merge-method: squash From 406d7e8a909330080b7a5ca4e965b2ceb80cb4a0 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Sun, 12 Sep 2021 23:52:02 +0900 Subject: [PATCH 226/851] Add sync rc develop action (#401) Signed-off-by: wep21 --- .github/workflows/sync-rc-develop.yml | 90 +++++++++++++++++++++++++++ 1 file changed, 90 insertions(+) create mode 100644 .github/workflows/sync-rc-develop.yml diff --git a/.github/workflows/sync-rc-develop.yml b/.github/workflows/sync-rc-develop.yml new file mode 100644 index 0000000000..7d63b51760 --- /dev/null +++ b/.github/workflows/sync-rc-develop.yml @@ -0,0 +1,90 @@ +name: sync rc develop + +on: + pull_request: + branches: + - "rc/*" + types: + - closed + workflow_dispatch: + inputs: + rc_branch: + description: "Target RC branch(e.g. rc/v1.0.0)" + required: true + +env: + BASE_BRANCH: develop + +jobs: + sync-rc: + runs-on: ubuntu-20.04 + + steps: + - name: Checkout repository + uses: actions/checkout@v2 + with: + ref: ${{ env.BASE_BRANCH }} + fetch-depth: 0 + + - name: Generate token + uses: tibdex/github-app-token@v1 + id: generate-token + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.APP_PRIVATE_KEY }} + + - name: Set SYNC_TARGET_BRANCH for pull_request event + if: github.event_name == 'pull_request' + run: | + echo "SYNC_TARGET_BRANCH=${{ github.base_ref }}" >> $GITHUB_ENV + - name: Set SYNC_TARGET_BRANCH for workflow_dispatch event + if: github.event_name == 'workflow_dispatch' + run: | + echo "SYNC_TARGET_BRANCH=${{ github.event.inputs.rc_branch }}" >> $GITHUB_ENV + - name: Set SYNC_BRANCH + run: | + echo ${SYNC_TARGET_BRANCH} | grep -e "^rc/v.*" + echo "SYNC_BRANCH=sync-rc/${SYNC_TARGET_BRANCH#refs/heads/}" >> $GITHUB_ENV + # To keep the base branch in "create-pull-request", checkout with "BASE_BRANCH" and reset to "SYNC_TARGET_BRANCH" + - name: Reset to sync target branch + run: | + git reset --hard origin/${{ env.SYNC_TARGET_BRANCH }} + - name: Set git config + run: | + git config --local user.email "actions@example.com" + git config --local user.name "Github Actions" + - name: Rebase on the base branch + run: | + for commit in $(git rev-list --left-only origin/${{ env.BASE_BRANCH }}...HEAD | tac); do + git rebase $commit || git rebase --abort + done + - name: Create PR + id: create_pr + uses: peter-evans/create-pull-request@v3 + with: + token: ${{ steps.generate-token.outputs.token }} + commit-message: sync rc develop + committer: GitHub + author: GitHub + signoff: false + base: ${{ env.BASE_BRANCH }} + branch: ${{ env.SYNC_BRANCH }} + delete-branch: true + title: sync rc develop + body: | + sync rc develop + labels: | + sync-rc-develop + draft: false + + - name: Check outputs + run: | + echo "Pull Request Number - ${{ steps.create_pr.outputs.pull-request-number }}" + echo "Pull Request URL - ${{ steps.create_pr.outputs.pull-request-url }}" + - name: Enable Auto-merge + if: steps.create_pr.outputs.pull-request-operation == 'created' + uses: peter-evans/enable-pull-request-automerge@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + pull-request-number: ${{ steps.create_pr.outputs.pull-request-number }} + merge-method: squash From 36021348e9665485b102455d4ba4e27815f862c2 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Mon, 13 Sep 2021 08:48:35 +0900 Subject: [PATCH 227/851] update rviz config (#399) * update rviz config * update config --- autoware_launch/rviz/autoware.rviz | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index a49557207d..6c3fe300b3 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -331,7 +331,7 @@ Visualization Manager: Channel Name: intensity Class: rviz_default_plugins/PointCloud2 Color: 255; 255; 255 - Color Transformer: Intensity + Color Transformer: FlatColor Decay Time: 0 Enabled: true Invert Rainbow: false @@ -344,7 +344,7 @@ Visualization Manager: Selectable: true Size (Pixels): 1 Size (m): 0.02 - Style: Squares + Style: Points Topic: Depth: 5 Durability Policy: Transient Local @@ -365,11 +365,13 @@ Visualization Manager: left_lane_bound: true parking_lots: true parking_space: true + pedestrian_marking: true right_lane_bound: true road_lanelets: false stop_lines: true traffic_light: true traffic_light_triangle: true + walkway_lanelets: true Topic: Depth: 5 Durability Policy: Transient Local @@ -383,7 +385,7 @@ Visualization Manager: Displays: - Class: rviz_common/Group Displays: - - Alpha: 0.999 + - Alpha: 0.4 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 5 @@ -404,9 +406,9 @@ Visualization Manager: Name: ConcatenatePointCloud Position Transformer: XYZ Selectable: true - Size (Pixels): 2 + Size (Pixels): 1 Size (m): 0.02 - Style: Squares + Style: Points Topic: Depth: 5 Durability Policy: Volatile @@ -425,7 +427,7 @@ Visualization Manager: Axis: Z Channel Name: z Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 + Color: 200; 200; 200 Color Transformer: FlatColor Decay Time: 0 Enabled: true @@ -437,9 +439,9 @@ Visualization Manager: Name: NoGroundPointCloud Position Transformer: XYZ Selectable: true - Size (Pixels): 5 + Size (Pixels): 3 Size (m): 0.02 - Style: Squares + Style: Points Topic: Depth: 5 Durability Policy: Volatile From 4879406e86ba03b141e6c11ce40659892bfcefcb Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 14 Sep 2021 09:55:25 +0900 Subject: [PATCH 228/851] Improve build-pr CI (#405) Signed-off-by: Kenji Miyake --- .github/get_modified_package.sh | 74 +++++++++++++++++++++++ .github/workflows/build_and_test_pr.yml | 5 +- .github/workflows/get_modified_package.sh | 62 ------------------- 3 files changed, 76 insertions(+), 65 deletions(-) create mode 100755 .github/get_modified_package.sh delete mode 100755 .github/workflows/get_modified_package.sh diff --git a/.github/get_modified_package.sh b/.github/get_modified_package.sh new file mode 100755 index 0000000000..da8a4f6e81 --- /dev/null +++ b/.github/get_modified_package.sh @@ -0,0 +1,74 @@ +#!/bin/bash +# Search for packages that have been modified from the main branch. +# Usage: get_modified_package.sh + +set -e + +SCRIPT_DIR=$(readlink -f "$(dirname "$0")") +ROOT_DIR=$(readlink -f "$SCRIPT_DIR"/../) + +# Parse arguments +args=() +while [ "${1:-}" != "" ]; do + case "$1" in + *) + args+=("$1") + ;; + esac + shift +done + +base_branch="${args[0]}" + +# Check args +if [ "$base_branch" = "" ]; then + echo -e "\e[31mPlease input a valid base_branch as the 1st argument.\e[m" + exit 1 +fi + +function find_package_dir() { + [ "$1" == "" ] && return 1 + + target_dir=$(dirname "$1") + while true ; do + parent_dir=$(dirname "$target_dir") + + # Exit if no parent found + if [ "$parent_dir" = "$target_dir" ] ; then + return 0 + fi + + # Output package name if package.xml found + if [ -f "$target_dir/package.xml" ] ; then + if [ ! -f "$target_dir/COLCON_IGNORE" ] ; then + echo "$target_dir" + return 0 + fi + fi + + # Move to parent dir + target_dir=$parent_dir + done + + return 1 +} + +# Find modified files from base branch +modified_files=$(git diff --name-only "$base_branch"...HEAD) + +# Find modified packages +modified_package_dirs=() +for modified_file in $modified_files; do + modified_package_dir=$(find_package_dir "$ROOT_DIR/$modified_file") + + if [ "$modified_package_dir" != "" ] ; then + modified_package_dirs+=("$modified_package_dir") + fi +done + +# Get package names from paths +modified_packages=$(colcon list --names-only --paths "${modified_package_dirs[@]}") + +# Output +# shellcheck disable=SC2086 +echo ::set-output name=package_list::$modified_packages diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml index 4998bcf9e6..144bff1611 100644 --- a/.github/workflows/build_and_test_pr.yml +++ b/.github/workflows/build_and_test_pr.yml @@ -2,7 +2,6 @@ name: Build and test for PR on: pull_request: - workflow_dispatch: jobs: build-and-test-pr: @@ -24,10 +23,10 @@ jobs: apt-get -y update apt-get -y install python3-pip - - name: Search modified package + - name: Search modified packages id: list_packages run: | - ${GITHUB_WORKSPACE}/.github/workflows/get_modified_package.sh + ${GITHUB_WORKSPACE}/.github/get_modified_package.sh origin/${{ github.base_ref }} - name: Show target packages run: | diff --git a/.github/workflows/get_modified_package.sh b/.github/workflows/get_modified_package.sh deleted file mode 100755 index 696d112d36..0000000000 --- a/.github/workflows/get_modified_package.sh +++ /dev/null @@ -1,62 +0,0 @@ -#!/bin/bash -# Search for packages that have been modified from the main branch. - -set -e - -SCRIPT_DIR=$(cd $(dirname $0); pwd) -ROOT_DIR=$(readlink -f $SCRIPT_DIR/../../) - -function get_package_name_from_xml() { - [ "$1" == "" ] && return 1 - - # Get tag in package.xml - sed -rz "s|.*\s*([a-zA-Z_0-9]+)\s*.*|\1|" < "$1" - - return 0 -} - -function find_package_from_file() { - [ "$1" == "" ] && return 1 - - target_dir=$(dirname $1) - while true ; do - parent_dir=$(dirname "$target_dir") - - # Exit if no parent found - if [ "$parent_dir" = "$target_dir" ] ; then - return 0 - fi - - # Output package name if package.xml found - if [ -f "$target_dir/package.xml" ] ; then - get_package_name_from_xml "$target_dir"/package.xml - return 0 - fi - - # Move to parent dir - target_dir=$parent_dir - done - - return 1 -} - -# Find modified files after merging origin/main -merge_base=$(git merge-base HEAD origin/main) -modified_files=$(git diff --name-only "$merge_base") - -# Find modified packages -for modified_file in $modified_files; do - modified_package=$(find_package_from_file "$ROOT_DIR/$modified_file") - - if [ "$modified_package" != "" ] ; then - modified_packages="$modified_packages $modified_package" - fi -done - -# Remove duplicates -# shellcheck disable=SC2086 -unique_modified_packages=$(printf "%s\n" $modified_packages | sort | uniq) - -# Output -# shellcheck disable=SC2086 -echo ::set-output name=package_list::$unique_modified_packages From ae8cbbdcc78dcf62d6cd2cacd9ac3ee926be06ab Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 14 Sep 2021 11:56:17 +0900 Subject: [PATCH 229/851] Add sync-public.yaml (#404) * Add sync-public.yaml Signed-off-by: Kenji Miyake * Add sync-public-develop.yaml Signed-off-by: Kenji Miyake --- .github/workflows/sync-public-develop.yaml | 40 ++++++++++++++++++++++ .github/workflows/sync-public.yaml | 40 ++++++++++++++++++++++ 2 files changed, 80 insertions(+) create mode 100644 .github/workflows/sync-public-develop.yaml create mode 100644 .github/workflows/sync-public.yaml diff --git a/.github/workflows/sync-public-develop.yaml b/.github/workflows/sync-public-develop.yaml new file mode 100644 index 0000000000..a6fc3aba39 --- /dev/null +++ b/.github/workflows/sync-public-develop.yaml @@ -0,0 +1,40 @@ +name: sync public + +on: + schedule: + - cron: "0 19 * * *" # run at 4 AM JST + workflow_dispatch: + +env: + BASE_BRANCH: develop + SYNC_TARGET_BRANCH: develop + SYNC_TARGET_REPOSITORY: https://github.com/tier4/AutowareArchitectureProposal_launcher.git + +jobs: + sync-public: + runs-on: ubuntu-20.04 + + steps: + - name: Checkout repository + uses: actions/checkout@v2 + with: + ref: ${{ env.BASE_BRANCH }} + fetch-depth: 0 + + - name: Generate token + uses: tibdex/github-app-token@v1 + id: generate-token + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.APP_PRIVATE_KEY }} + + - name: Set git config for private repositories + run: | + git config --local --unset-all http.https://github.com/.extraheader || true + git config --global url.https://x-access-token:${{ steps.generate-token.outputs.token }}@github.com.insteadOf 'https://github.com' + + - name: Push to public repository + run: | + git remote add public ${{ env.SYNC_TARGET_REPOSITORY }} + git fetch public + git push public ${{ env.BASE_BRANCH }}:${{ env.SYNC_TARGET_BRANCH }} diff --git a/.github/workflows/sync-public.yaml b/.github/workflows/sync-public.yaml new file mode 100644 index 0000000000..82ed0cce74 --- /dev/null +++ b/.github/workflows/sync-public.yaml @@ -0,0 +1,40 @@ +name: sync public + +on: + schedule: + - cron: "0 19 * * *" # run at 4 AM JST + workflow_dispatch: + +env: + BASE_BRANCH: main + SYNC_TARGET_BRANCH: main + SYNC_TARGET_REPOSITORY: https://github.com/tier4/AutowareArchitectureProposal_launcher.git + +jobs: + sync-public: + runs-on: ubuntu-20.04 + + steps: + - name: Checkout repository + uses: actions/checkout@v2 + with: + ref: ${{ env.BASE_BRANCH }} + fetch-depth: 0 + + - name: Generate token + uses: tibdex/github-app-token@v1 + id: generate-token + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.APP_PRIVATE_KEY }} + + - name: Set git config for private repositories + run: | + git config --local --unset-all http.https://github.com/.extraheader || true + git config --global url.https://x-access-token:${{ steps.generate-token.outputs.token }}@github.com.insteadOf 'https://github.com' + + - name: Push to public repository + run: | + git remote add public ${{ env.SYNC_TARGET_REPOSITORY }} + git fetch public + git push public ${{ env.BASE_BRANCH }}:${{ env.SYNC_TARGET_BRANCH }} From a4d3d065efddf899bb1fbb878da0102411f1e4ff Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Wed, 15 Sep 2021 09:52:16 +0900 Subject: [PATCH 230/851] Fix pre-commit (#407) * Fix pre-commit errors Signed-off-by: Kenji Miyake * Fix package.xml Signed-off-by: Kenji Miyake --- autoware_api_launch/package.xml | 2 +- autoware_launch/package.xml | 17 +++++------------ control_launch/package.xml | 4 ++-- integration_launch/package.xml | 13 ++++--------- localization_launch/package.xml | 4 ++-- perception_launch/README.md | 1 - perception_launch/package.xml | 11 ++++------- planning_launch/launch/planning.launch.xml | 2 +- sensing_launch/package.xml | 4 ++-- system_launch/package.xml | 4 ++-- vehicle_launch/README.md | 8 ++++---- vehicle_launch/package.xml | 2 +- 12 files changed, 28 insertions(+), 44 deletions(-) diff --git a/autoware_api_launch/package.xml b/autoware_api_launch/package.xml index f8698287b9..b9b064d9b4 100644 --- a/autoware_api_launch/package.xml +++ b/autoware_api_launch/package.xml @@ -10,9 +10,9 @@ ament_cmake_auto - awapi_awiv_adapter autoware_iv_external_api_adaptor autoware_iv_internal_api_adaptor + awapi_awiv_adapter path_distance_calculator topic_tools diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 8a744017b4..c564859851 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -9,28 +9,21 @@ ament_cmake_auto - autoware_api_launch + autoware_global_parameter_loader + autoware_web_controller control_launch localization_launch map_launch perception_launch planning_launch + python3-bson + python3-tornado + rviz2 sensing_launch system_launch vehicle_launch - - rviz2 - - - autoware_global_parameter_loader - autoware_web_controller - python-tornado - python3-tornado - python-bson - python3-bson - ament_lint_auto ament_lint_common diff --git a/control_launch/package.xml b/control_launch/package.xml index fd1003d974..6c44b73f85 100644 --- a/control_launch/package.xml +++ b/control_launch/package.xml @@ -11,14 +11,14 @@ ament_cmake_auto + external_cmd_converter + lane_departure_checker latlon_muxer mpc_follower pure_pursuit - external_cmd_converter shift_decider vehicle_cmd_gate velocity_controller - lane_departure_checker ament_lint_auto ament_lint_common diff --git a/integration_launch/package.xml b/integration_launch/package.xml index dc8da62d65..9bafa3c34a 100644 --- a/integration_launch/package.xml +++ b/integration_launch/package.xml @@ -8,24 +8,19 @@ Apache 2 ament_cmake_auto - + autoware_web_controller control_launch localization_launch map_launch perception_launch planning_launch + python3-bson + python3-tornado + rviz2 sensing_launch system_launch vehicle_launch - - rviz2 - - - autoware_web_controller - python3-tornado - python3-bson - ament_lint_auto ament_lint_common diff --git a/localization_launch/package.xml b/localization_launch/package.xml index 8ac75637ba..bd01526b20 100644 --- a/localization_launch/package.xml +++ b/localization_launch/package.xml @@ -11,11 +11,11 @@ ament_cmake_auto - ndt_scan_matcher ekf_localizer gyro_odometer - pose_initializer + ndt_scan_matcher pointcloud_preprocessor + pose_initializer topic_tools ament_lint_auto diff --git a/perception_launch/README.md b/perception_launch/README.md index 4040422890..9cc11ca6f7 100644 --- a/perception_launch/README.md +++ b/perception_launch/README.md @@ -12,7 +12,6 @@ Please see `` in `package.xml`. You can include as follows in `*.launch.xml` to use `perception.launch.xml`. - ```xml diff --git a/perception_launch/package.xml b/perception_launch/package.xml index 38fe7e3761..35ed04f900 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -10,24 +10,21 @@ ament_cmake_auto - dynamic_object_visualization euclidean_cluster + image_transport_decompressor lidar_apollo_instance_segmentation map_based_prediction multi_object_tracker naive_path_prediction + object_merger + object_range_splitter roi_cluster_fusion shape_estimation tensorrt_yolo - object_range_splitter - object_merger - - - image_transport_decompressor + traffic_light_classifier traffic_light_map_based_detector traffic_light_ssd_fine_detector - traffic_light_classifier traffic_light_visualization ament_lint_auto diff --git a/planning_launch/launch/planning.launch.xml b/planning_launch/launch/planning.launch.xml index 3f33650f47..640b3a234b 100644 --- a/planning_launch/launch/planning.launch.xml +++ b/planning_launch/launch/planning.launch.xml @@ -21,6 +21,6 @@ - + diff --git a/sensing_launch/package.xml b/sensing_launch/package.xml index bce6c40edd..13b7bc9276 100644 --- a/sensing_launch/package.xml +++ b/sensing_launch/package.xml @@ -17,11 +17,11 @@ topic_tools ublox_gps usb_cam - + usb_cam velodyne_driver velodyne_monitor velodyne_pointcloud - usb_cam + ament_lint_auto ament_lint_common diff --git a/system_launch/package.xml b/system_launch/package.xml index 21ff9552c9..64664d8435 100644 --- a/system_launch/package.xml +++ b/system_launch/package.xml @@ -10,11 +10,11 @@ ament_cmake_auto - system_monitor - autoware_state_monitor autoware_error_monitor + autoware_state_monitor autoware_version emergency_handler + system_monitor ament_lint_auto ament_lint_common diff --git a/vehicle_launch/README.md b/vehicle_launch/README.md index de5d447d47..eba3f836a3 100644 --- a/vehicle_launch/README.md +++ b/vehicle_launch/README.md @@ -49,10 +49,10 @@ ex.) ### Arguments -| Name | Type | Description | Default | -| ------------- | ------ | ------------------ | ------------------ | -| sensor_model | String | sensor model name | "" | -| vehicle_model | String | vehicle model name | "" | +| Name | Type | Description | Default | +| ------------- | ------ | ------------------ | ------- | +| sensor_model | String | sensor model name | "" | +| vehicle_model | String | vehicle model name | "" | ### Usage diff --git a/vehicle_launch/package.xml b/vehicle_launch/package.xml index d9d663ace1..c463f17c29 100644 --- a/vehicle_launch/package.xml +++ b/vehicle_launch/package.xml @@ -13,9 +13,9 @@ camera_description imu_description livox_description - velodyne_description robot_state_publisher simple_planning_simulator + velodyne_description xacro ament_lint_auto From 02de68696db91ea0dce24642f5138a54bc5e519f Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Wed, 15 Sep 2021 09:54:44 +0900 Subject: [PATCH 231/851] Add pre-commit (#406) * Add pre-commit Signed-off-by: Kenji Miyake * Add sort-package-xml Signed-off-by: Kenji Miyake --- .github/workflows/pre-commit.yaml | 21 +++++++++++ .markdownlint.yaml | 6 ++++ .pre-commit-config.yaml | 58 +++++++++++++++++++++++++++++++ .prettierrc.yaml | 2 ++ 4 files changed, 87 insertions(+) create mode 100644 .github/workflows/pre-commit.yaml create mode 100644 .markdownlint.yaml create mode 100644 .pre-commit-config.yaml create mode 100644 .prettierrc.yaml diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml new file mode 100644 index 0000000000..22e56ca2b6 --- /dev/null +++ b/.github/workflows/pre-commit.yaml @@ -0,0 +1,21 @@ +name: pre-commit + +on: + pull_request: + workflow_dispatch: + +jobs: + pre-commit: + runs-on: ubuntu-latest + + steps: + - name: Checkout repository + uses: actions/checkout@v2 + with: + fetch-depth: 0 + + - name: Setup Python + uses: actions/setup-python@v2 + + - name: Run pre-commit + uses: pre-commit/action@v2.0.3 diff --git a/.markdownlint.yaml b/.markdownlint.yaml new file mode 100644 index 0000000000..605ac41ce9 --- /dev/null +++ b/.markdownlint.yaml @@ -0,0 +1,6 @@ +default: true +MD013: false +MD024: + siblings_only: true +MD033: false +MD041: false diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml new file mode 100644 index 0000000000..5b8232fe21 --- /dev/null +++ b/.pre-commit-config.yaml @@ -0,0 +1,58 @@ +# To install: +# +# pip install pre-commit +# +# To use: +# +# pre-commit run -a +# +# Or: +# +# pre-commit install # (runs every time you commit in git) +# +# To update this file: +# +# pre-commit autoupdate +# +# See https://github.com/pre-commit/pre-commit + +repos: + # Standard hooks + - repo: https://github.com/pre-commit/pre-commit-hooks + rev: v4.0.1 + hooks: + - id: check-json + - id: check-merge-conflict + - id: check-toml + - id: check-xml + - id: check-yaml + - id: detect-private-key + - id: double-quote-string-fixer + - id: end-of-file-fixer + - id: mixed-line-ending + - id: trailing-whitespace + args: [--markdown-linebreak-ext=md] + + - repo: https://github.com/igorshubovych/markdownlint-cli + rev: v0.27.1 + hooks: + - id: markdownlint + args: ["-c", ".markdownlint.yaml", "--fix"] + + - repo: https://github.com/pre-commit/mirrors-prettier + rev: v2.3.2 + hooks: + - id: prettier + + - repo: https://github.com/tier4/pre-commit-hooks-ros + rev: v0.1.2 + hooks: + - id: prettier-xml + - id: sort-package-xml + + - repo: https://github.com/gruntwork-io/pre-commit + rev: v0.1.12 + hooks: + - id: shellcheck + +exclude: "(.svg|.rviz|.param.yaml|traffic_light_camera.yaml)" diff --git a/.prettierrc.yaml b/.prettierrc.yaml new file mode 100644 index 0000000000..ef9b1b85a7 --- /dev/null +++ b/.prettierrc.yaml @@ -0,0 +1,2 @@ +printWidth: 120 +tabWidth: 2 From 9d18358bf2fbec02fbad9387d535a3fc31935550 Mon Sep 17 00:00:00 2001 From: Taichi Higashide Date: Wed, 15 Sep 2021 16:57:43 +0900 Subject: [PATCH 232/851] Update system.launch.xml (#411) --- system_launch/launch/system.launch.xml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index 4a1baa6090..d21ef0fd45 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -35,18 +35,19 @@ + + - From 4ebd637e75e4c5ec7f2b9d26c2bc94b39feb6f4d Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Wed, 15 Sep 2021 18:37:22 +0900 Subject: [PATCH 233/851] Handle empty output in get_modified_package.sh (#412) Signed-off-by: Kenji Miyake --- .github/get_modified_package.sh | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/.github/get_modified_package.sh b/.github/get_modified_package.sh index da8a4f6e81..cc99e534a4 100755 --- a/.github/get_modified_package.sh +++ b/.github/get_modified_package.sh @@ -67,7 +67,9 @@ for modified_file in $modified_files; do done # Get package names from paths -modified_packages=$(colcon list --names-only --paths "${modified_package_dirs[@]}") +if [ "${#modified_package_dirs[@]}" != "0" ] ; then + modified_packages=$(colcon list --names-only --paths "${modified_package_dirs[@]}") +fi # Output # shellcheck disable=SC2086 From 8cd04aabd4f07d867bd9f3d77241550a5b9263ab Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Thu, 16 Sep 2021 14:05:05 +0900 Subject: [PATCH 234/851] Change proposal sync app ID (#414) Signed-off-by: Kenji Miyake --- .github/workflows/sync-public-develop.yaml | 4 ++-- .github/workflows/sync-public.yaml | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/sync-public-develop.yaml b/.github/workflows/sync-public-develop.yaml index a6fc3aba39..874b81344c 100644 --- a/.github/workflows/sync-public-develop.yaml +++ b/.github/workflows/sync-public-develop.yaml @@ -25,8 +25,8 @@ jobs: uses: tibdex/github-app-token@v1 id: generate-token with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.APP_PRIVATE_KEY }} + app_id: ${{ secrets.PROPOSAL_SYNC_APP_ID }} + private_key: ${{ secrets.PROPOSAL_SYNC_APP_PRIVATE_KEY }} - name: Set git config for private repositories run: | diff --git a/.github/workflows/sync-public.yaml b/.github/workflows/sync-public.yaml index 82ed0cce74..8cc1453bf3 100644 --- a/.github/workflows/sync-public.yaml +++ b/.github/workflows/sync-public.yaml @@ -25,8 +25,8 @@ jobs: uses: tibdex/github-app-token@v1 id: generate-token with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.APP_PRIVATE_KEY }} + app_id: ${{ secrets.PROPOSAL_SYNC_APP_ID }} + private_key: ${{ secrets.PROPOSAL_SYNC_APP_PRIVATE_KEY }} - name: Set git config for private repositories run: | From ff36c12dc454a318473dfc30351ec17241a6bcfb Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Mon, 27 Sep 2021 13:03:59 +0900 Subject: [PATCH 235/851] Judge merge base in sync rc (#422) Signed-off-by: wep21 --- .github/workflows/sync-rc-develop.yml | 90 --------------------------- .github/workflows/sync-rc.yml | 38 ++++++++--- 2 files changed, 30 insertions(+), 98 deletions(-) delete mode 100644 .github/workflows/sync-rc-develop.yml diff --git a/.github/workflows/sync-rc-develop.yml b/.github/workflows/sync-rc-develop.yml deleted file mode 100644 index 7d63b51760..0000000000 --- a/.github/workflows/sync-rc-develop.yml +++ /dev/null @@ -1,90 +0,0 @@ -name: sync rc develop - -on: - pull_request: - branches: - - "rc/*" - types: - - closed - workflow_dispatch: - inputs: - rc_branch: - description: "Target RC branch(e.g. rc/v1.0.0)" - required: true - -env: - BASE_BRANCH: develop - -jobs: - sync-rc: - runs-on: ubuntu-20.04 - - steps: - - name: Checkout repository - uses: actions/checkout@v2 - with: - ref: ${{ env.BASE_BRANCH }} - fetch-depth: 0 - - - name: Generate token - uses: tibdex/github-app-token@v1 - id: generate-token - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.APP_PRIVATE_KEY }} - - - name: Set SYNC_TARGET_BRANCH for pull_request event - if: github.event_name == 'pull_request' - run: | - echo "SYNC_TARGET_BRANCH=${{ github.base_ref }}" >> $GITHUB_ENV - - name: Set SYNC_TARGET_BRANCH for workflow_dispatch event - if: github.event_name == 'workflow_dispatch' - run: | - echo "SYNC_TARGET_BRANCH=${{ github.event.inputs.rc_branch }}" >> $GITHUB_ENV - - name: Set SYNC_BRANCH - run: | - echo ${SYNC_TARGET_BRANCH} | grep -e "^rc/v.*" - echo "SYNC_BRANCH=sync-rc/${SYNC_TARGET_BRANCH#refs/heads/}" >> $GITHUB_ENV - # To keep the base branch in "create-pull-request", checkout with "BASE_BRANCH" and reset to "SYNC_TARGET_BRANCH" - - name: Reset to sync target branch - run: | - git reset --hard origin/${{ env.SYNC_TARGET_BRANCH }} - - name: Set git config - run: | - git config --local user.email "actions@example.com" - git config --local user.name "Github Actions" - - name: Rebase on the base branch - run: | - for commit in $(git rev-list --left-only origin/${{ env.BASE_BRANCH }}...HEAD | tac); do - git rebase $commit || git rebase --abort - done - - name: Create PR - id: create_pr - uses: peter-evans/create-pull-request@v3 - with: - token: ${{ steps.generate-token.outputs.token }} - commit-message: sync rc develop - committer: GitHub - author: GitHub - signoff: false - base: ${{ env.BASE_BRANCH }} - branch: ${{ env.SYNC_BRANCH }} - delete-branch: true - title: sync rc develop - body: | - sync rc develop - labels: | - sync-rc-develop - draft: false - - - name: Check outputs - run: | - echo "Pull Request Number - ${{ steps.create_pr.outputs.pull-request-number }}" - echo "Pull Request URL - ${{ steps.create_pr.outputs.pull-request-url }}" - - name: Enable Auto-merge - if: steps.create_pr.outputs.pull-request-operation == 'created' - uses: peter-evans/enable-pull-request-automerge@v1 - with: - token: ${{ steps.generate-token.outputs.token }} - pull-request-number: ${{ steps.create_pr.outputs.pull-request-number }} - merge-method: squash diff --git a/.github/workflows/sync-rc.yml b/.github/workflows/sync-rc.yml index f3a6a35084..a45496720d 100644 --- a/.github/workflows/sync-rc.yml +++ b/.github/workflows/sync-rc.yml @@ -12,9 +12,6 @@ on: description: "Target RC branch(e.g. rc/v1.0.0)" required: true -env: - BASE_BRANCH: main - jobs: sync-rc: runs-on: ubuntu-20.04 @@ -23,7 +20,6 @@ jobs: - name: Checkout repository uses: actions/checkout@v2 with: - ref: ${{ env.BASE_BRANCH }} fetch-depth: 0 - name: Generate token @@ -48,6 +44,31 @@ jobs: echo ${SYNC_TARGET_BRANCH} | grep -e "^rc/v.*" echo "SYNC_BRANCH=sync-rc/${SYNC_TARGET_BRANCH#refs/heads/}" >> $GITHUB_ENV + - name: Judge BASE_BRANCH + run: | + function is_main_base() { + target_branch="$1" + + main_base=$(git merge-base "${target_branch}" origin/main) + develop_base=$(git merge-base "${target_branch}" origin/develop) + + return $(test "${main_base}" = "${develop_base}") + } + + if is_main_base "origin/${{ env.SYNC_TARGET_BRANCH }}"; then + base_branch=main + else + base_branch=develop + fi + + echo "BASE_BRANCH=${base_branch}" >> $GITHUB_ENV + + - name: Checkout repository + uses: actions/checkout@v2 + with: + ref: ${{ env.BASE_BRANCH }} + fetch-depth: 0 + # To keep the base branch in "create-pull-request", checkout with "BASE_BRANCH" and reset to "SYNC_TARGET_BRANCH" - name: Reset to sync target branch run: | @@ -60,8 +81,9 @@ jobs: - name: Rebase on the base branch run: | - for commit in $(git rev-list --left-only origin/${{ env.BASE_BRANCH }}...HEAD | tac); do - git rebase $commit || git rebase --abort + for commit in $(git rev-list --left-only "origin/${{ env.BASE_BRANCH }}"...HEAD | tac); do + merge_base=$(git merge-base HEAD "origin/${{ env.BASE_BRANCH }}") + git rebase --onto "$commit" "$merge_base" "${{ env.BASE_BRANCH }}" || git rebase --abort done - name: Create PR @@ -76,9 +98,9 @@ jobs: base: ${{ env.BASE_BRANCH }} branch: ${{ env.SYNC_BRANCH }} delete-branch: true - title: sync rc + title: sync rc ${{ env.SYNC_TARGET_BRANCH }} body: | - sync rc + sync rc ${{ env.SYNC_TARGET_BRANCH }} labels: | sync-rc draft: false From 1ccc97034f84f67d8ff000a308b58ffa9be58091 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Mon, 27 Sep 2021 16:06:58 +0900 Subject: [PATCH 236/851] modify util.launch in localization_launch #396 --- ...op_box_filter_measurement_range.param.yaml | 11 ++ .../random_downsample_filter.param.yaml | 3 + .../config/voxel_grid_filter.param.yaml | 5 + .../launch/util/util.launch.py | 106 ++++++++++++++---- .../launch/util/util.launch.xml | 3 - 5 files changed, 104 insertions(+), 24 deletions(-) create mode 100644 localization_launch/config/crop_box_filter_measurement_range.param.yaml create mode 100644 localization_launch/config/random_downsample_filter.param.yaml create mode 100644 localization_launch/config/voxel_grid_filter.param.yaml diff --git a/localization_launch/config/crop_box_filter_measurement_range.param.yaml b/localization_launch/config/crop_box_filter_measurement_range.param.yaml new file mode 100644 index 0000000000..ad55423154 --- /dev/null +++ b/localization_launch/config/crop_box_filter_measurement_range.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + input_frame: "base_link" + output_frame: "base_link" + 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 diff --git a/localization_launch/config/random_downsample_filter.param.yaml b/localization_launch/config/random_downsample_filter.param.yaml new file mode 100644 index 0000000000..53be849e0a --- /dev/null +++ b/localization_launch/config/random_downsample_filter.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + sample_num: 1500 diff --git a/localization_launch/config/voxel_grid_filter.param.yaml b/localization_launch/config/voxel_grid_filter.param.yaml new file mode 100644 index 0000000000..51a7ee9d89 --- /dev/null +++ b/localization_launch/config/voxel_grid_filter.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + voxel_size_x: 3.0 + voxel_size_y: 3.0 + voxel_size_z: 3.0 diff --git a/localization_launch/launch/util/util.launch.py b/localization_launch/launch/util/util.launch.py index bde66951be..055eca0450 100644 --- a/localization_launch/launch/util/util.launch.py +++ b/localization_launch/launch/util/util.launch.py @@ -13,13 +13,22 @@ # limitations under the License. import launch +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction from launch.conditions import LaunchConfigurationNotEquals from launch.substitutions import LaunchConfiguration from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode +from launch_ros.substitutions import FindPackageShare +import yaml -def generate_launch_description(): +def launch_setup(context, *args, **kwargs): + # https://github.com/ros2/launch_ros/issues/156 + def load_composable_node_param(param_path): + with open(LaunchConfiguration(param_path).perform(context), 'r') as f: + return yaml.safe_load(f)['/**']['ros__parameters'] + crop_box_component = ComposableNode( package='pointcloud_preprocessor', plugin='pointcloud_preprocessor::CropBoxFilterComponent', @@ -29,17 +38,9 @@ def generate_launch_description(): ('output', LaunchConfiguration('output_measurement_range_sensor_points_topic')), ], - parameters=[{ - 'input_frame': LaunchConfiguration('base_frame'), - 'output_frame': LaunchConfiguration('base_frame'), - '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, - }], + parameters=[ + load_composable_node_param('crop_box_filter_measurement_range_param_path'), + ], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') }], @@ -54,11 +55,7 @@ def generate_launch_description(): ('output', LaunchConfiguration('output_voxel_grid_downsample_sensor_points_topic')), ], - parameters=[{ - 'voxel_size_x': 3.0, - 'voxel_size_y': 3.0, - 'voxel_size_z': 3.0, - }], + parameters=[load_composable_node_param('voxel_grid_downsample_filter_param_path')], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') }], @@ -73,9 +70,9 @@ def generate_launch_description(): ('output', LaunchConfiguration('output_downsample_sensor_points_topic')), ], - parameters=[{ - 'sample_num': 1500, - }], + parameters=[ + load_composable_node_param('random_downsample_filter_param_path') + ], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') }], @@ -90,4 +87,71 @@ def generate_launch_description(): composable_node_descriptions=composable_nodes, target_container=LaunchConfiguration('container'), ) - return launch.LaunchDescription([load_composable_nodes]) + + return [load_composable_nodes] + + +def generate_launch_description(): + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None, description=None): + arg = DeclareLaunchArgument(name, default_value=default_value, description=description) + launch_arguments.append(arg) + + add_launch_arg( + 'crop_box_filter_measurement_range_param_path', + [ + FindPackageShare('localization_launch'), + '/config/crop_box_filter_measurement_range.param.yaml' + ], + 'path to the parameter file of crop_box_filter_measurement_range' + ) + add_launch_arg( + 'voxel_grid_downsample_filter_param_path', + [ + FindPackageShare('localization_launch'), + '/config/voxel_grid_filter.param.yaml' + ], + 'path to the parameter file of voxel_grid_downsample_filter' + ) + add_launch_arg( + 'random_downsample_filter_param_path', + [ + FindPackageShare('localization_launch'), + '/config/random_downsample_filter.param.yaml' + ], + 'path to the parameter file of random_downsample_filter' + ) + add_launch_arg('use_intra_process', 'true', 'use ROS2 component container communication') + add_launch_arg( + 'container', + '/sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container', + 'container name' + ) + add_launch_arg( + 'input_sensor_points_topic', + '/sensing/lidar/top/rectified/pointcloud', + 'input topic name for raw pointcloud' + ) + add_launch_arg( + 'output_measurement_range_sensor_points_topic', + 'measurement_range/pointcloud', + 'output topic name for crop box filter' + ) + add_launch_arg( + 'output_voxel_grid_downsample_sensor_points_topic', + 'voxel_grid_downsample/pointcloud', + 'output topic name for voxel grid downsample filter' + ) + add_launch_arg( + 'output_downsample_sensor_points_topic', + 'downsample/pointcloud', + 'output topic name for downsample filter. this is final output' + ) + + return launch.LaunchDescription( + launch_arguments + + [ + OpaqueFunction(function=launch_setup) + ] + ) diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 5ea9bfce95..6d2cc29549 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -7,9 +7,6 @@ - - - From efe60c66cb1c64785b7ea78118b926f7c7a3487d Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Tue, 28 Sep 2021 09:28:02 +0900 Subject: [PATCH 237/851] add update-pre-commit job (#423) --- .github/workflows/update-pre-commit.yml | 42 +++++++++++++++++++++++++ 1 file changed, 42 insertions(+) create mode 100644 .github/workflows/update-pre-commit.yml diff --git a/.github/workflows/update-pre-commit.yml b/.github/workflows/update-pre-commit.yml new file mode 100644 index 0000000000..f18fd62386 --- /dev/null +++ b/.github/workflows/update-pre-commit.yml @@ -0,0 +1,42 @@ +name: Update pre-commit + +on: + schedule: + - cron: "0 19 * * *" # run at 4 AM JST + workflow_dispatch: + +jobs: + update-pre-commit: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v2 + + - name: Generate token + uses: tibdex/github-app-token@v1 + id: generate-token + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.APP_PRIVATE_KEY }} + + - name: Setup Python + uses: actions/setup-python@v2 + with: + python-version: 3.8 + + - name: Install pre-commit + run: pip install pre-commit + + - name: Run pre-commit autoupdate + run: pre-commit autoupdate + + - name: Create Pull Request + uses: peter-evans/create-pull-request@v3 + with: + token: ${{ steps.generate-token.outputs.token }} + base: main + branch: update/pre-commit-autoupdate + title: Auto-update pre-commit hooks + commit-message: Auto-update pre-commit hooks + body: | + Update versions of tools in pre-commit configs to latest version + labels: dependencies From 7a84b68e0cbbb13be3852f25b5cf4c7044018b8b Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Tue, 28 Sep 2021 12:20:25 +0900 Subject: [PATCH 238/851] update pre-commit-hooks-ros to v0.2.0 (#425) --- .pre-commit-config.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 5b8232fe21..c46b1b0ff9 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -45,9 +45,9 @@ repos: - id: prettier - repo: https://github.com/tier4/pre-commit-hooks-ros - rev: v0.1.2 + rev: v0.2.0 hooks: - - id: prettier-xml + - id: prettier-package-xml - id: sort-package-xml - repo: https://github.com/gruntwork-io/pre-commit From fb68263926381e33593fc9b794fcd6134a5a768a Mon Sep 17 00:00:00 2001 From: "autoware-iv-sync-ci[bot]" <87871706+autoware-iv-sync-ci[bot]@users.noreply.github.com> Date: Tue, 28 Sep 2021 12:26:19 +0900 Subject: [PATCH 239/851] Auto-update pre-commit hooks (#426) Co-authored-by: KeisukeShima --- .pre-commit-config.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index c46b1b0ff9..3902e171df 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -34,13 +34,13 @@ repos: args: [--markdown-linebreak-ext=md] - repo: https://github.com/igorshubovych/markdownlint-cli - rev: v0.27.1 + rev: v0.28.1 hooks: - id: markdownlint args: ["-c", ".markdownlint.yaml", "--fix"] - repo: https://github.com/pre-commit/mirrors-prettier - rev: v2.3.2 + rev: v2.4.1 hooks: - id: prettier @@ -51,7 +51,7 @@ repos: - id: sort-package-xml - repo: https://github.com/gruntwork-io/pre-commit - rev: v0.1.12 + rev: v0.1.15 hooks: - id: shellcheck From b9fcdb4c0aa3df40485d79c6879cf04b5bb6526f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 28 Sep 2021 22:22:24 +0900 Subject: [PATCH 240/851] Bump streetsidesoftware/cspell-action from 1.3.1 to 1.3.2 (#427) Bumps [streetsidesoftware/cspell-action](https://github.com/streetsidesoftware/cspell-action) from 1.3.1 to 1.3.2. - [Release notes](https://github.com/streetsidesoftware/cspell-action/releases) - [Changelog](https://github.com/streetsidesoftware/cspell-action/blob/main/CHANGELOG.md) - [Commits](https://github.com/streetsidesoftware/cspell-action/compare/v1.3.1...v1.3.2) --- updated-dependencies: - dependency-name: streetsidesoftware/cspell-action dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/spell_check_pr.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/spell_check_pr.yml b/.github/workflows/spell_check_pr.yml index 93bf74ac4c..bffc9ff7bf 100644 --- a/.github/workflows/spell_check_pr.yml +++ b/.github/workflows/spell_check_pr.yml @@ -16,6 +16,6 @@ jobs: --output .github/workflows/.cspell.json \ https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json - - uses: streetsidesoftware/cspell-action@v1.3.1 + - uses: streetsidesoftware/cspell-action@v1.3.2 with: config: ".github/workflows/.cspell.json" From dfbed2be4155b5cdee04e27f7103608cfd79f494 Mon Sep 17 00:00:00 2001 From: YamatoAndo Date: Thu, 30 Sep 2021 14:43:50 +0900 Subject: [PATCH 241/851] add localization error monitor param (#431) --- localization_launch/launch/localization.launch.xml | 3 +-- .../localization_error_monitor.launch.xml | 11 +++++++++++ 2 files changed, 12 insertions(+), 2 deletions(-) create mode 100644 localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml diff --git a/localization_launch/launch/localization.launch.xml b/localization_launch/launch/localization.launch.xml index fe8e93c0c9..3deae2b0e4 100644 --- a/localization_launch/launch/localization.launch.xml +++ b/localization_launch/launch/localization.launch.xml @@ -28,8 +28,7 @@ - - + diff --git a/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml b/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml new file mode 100644 index 0000000000..d2ea9ced7b --- /dev/null +++ b/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml @@ -0,0 +1,11 @@ + + + + + + + + + + + From 18b3a4fef6cd40ac481d75d5f8e1ce71a4865496 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 4 Oct 2021 12:35:08 +0900 Subject: [PATCH 242/851] Fix pre-commit target (#436) Signed-off-by: Kenji Miyake --- .pre-commit-config.yaml | 3 ++- sensing_launch/data/traffic_light_camera.yaml | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 3902e171df..c494a64fdd 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -43,6 +43,7 @@ repos: rev: v2.4.1 hooks: - id: prettier + exclude: "(.rviz|.param.yaml|traffic_light_camera.yaml)" - repo: https://github.com/tier4/pre-commit-hooks-ros rev: v0.2.0 @@ -55,4 +56,4 @@ repos: hooks: - id: shellcheck -exclude: "(.svg|.rviz|.param.yaml|traffic_light_camera.yaml)" +exclude: "(.svg)" diff --git a/sensing_launch/data/traffic_light_camera.yaml b/sensing_launch/data/traffic_light_camera.yaml index a4c99fae96..458ad17ca2 100644 --- a/sensing_launch/data/traffic_light_camera.yaml +++ b/sensing_launch/data/traffic_light_camera.yaml @@ -17,4 +17,4 @@ rectification_matrix: 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 + 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] From 8b34d153e8a507426c650ab1ce6fa7d3830df144 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Tue, 5 Oct 2021 22:22:21 +0900 Subject: [PATCH 243/851] Add emergency status API (#439) --- control_launch/launch/control.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 088885eccd..292e13bf53 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -197,6 +197,7 @@ def launch_setup(context, *args, **kwargs): ('output/turn_signal_cmd', '/control/turn_signal_cmd'), ('output/gate_mode', '/control/current_gate_mode'), ('output/engage', '/api/autoware/get/engage'), + ('output/external_emergency', '/api/autoware/get/emergency'), ('~/service/engage', '/api/autoware/set/engage'), ('~/service/external_emergency', '/api/autoware/set/emergency'), From 12e2a39e3d85a8dfa185603786189101fe2f07bd Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 6 Oct 2021 08:36:16 +0900 Subject: [PATCH 244/851] Bump streetsidesoftware/cspell-action from 1.3.2 to 1.3.3 (#440) Bumps [streetsidesoftware/cspell-action](https://github.com/streetsidesoftware/cspell-action) from 1.3.2 to 1.3.3. - [Release notes](https://github.com/streetsidesoftware/cspell-action/releases) - [Changelog](https://github.com/streetsidesoftware/cspell-action/blob/main/CHANGELOG.md) - [Commits](https://github.com/streetsidesoftware/cspell-action/compare/v1.3.2...v1.3.3) --- updated-dependencies: - dependency-name: streetsidesoftware/cspell-action dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/spell_check_pr.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/spell_check_pr.yml b/.github/workflows/spell_check_pr.yml index bffc9ff7bf..484a0e9447 100644 --- a/.github/workflows/spell_check_pr.yml +++ b/.github/workflows/spell_check_pr.yml @@ -16,6 +16,6 @@ jobs: --output .github/workflows/.cspell.json \ https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json - - uses: streetsidesoftware/cspell-action@v1.3.2 + - uses: streetsidesoftware/cspell-action@v1.3.3 with: config: ".github/workflows/.cspell.json" From 12693d276db9b58b8288c95a04b54b4833d9c4d8 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 7 Oct 2021 15:18:20 +0900 Subject: [PATCH 245/851] Remove aip xx2 model from sensing launch (#446) Signed-off-by: wep21 --- .../launch/aip_xx2/camera.launch.xml | 24 --- sensing_launch/launch/aip_xx2/gnss.launch.xml | 31 --- sensing_launch/launch/aip_xx2/imu.launch.xml | 24 --- .../launch/aip_xx2/lidar.launch.xml | 56 ----- .../aip_xx2/pointcloud_preprocessor.launch.py | 193 ------------------ 5 files changed, 328 deletions(-) delete mode 100644 sensing_launch/launch/aip_xx2/camera.launch.xml delete mode 100644 sensing_launch/launch/aip_xx2/gnss.launch.xml delete mode 100644 sensing_launch/launch/aip_xx2/imu.launch.xml delete mode 100644 sensing_launch/launch/aip_xx2/lidar.launch.xml delete mode 100644 sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py diff --git a/sensing_launch/launch/aip_xx2/camera.launch.xml b/sensing_launch/launch/aip_xx2/camera.launch.xml deleted file mode 100644 index 617d5fbb68..0000000000 --- a/sensing_launch/launch/aip_xx2/camera.launch.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx2/gnss.launch.xml b/sensing_launch/launch/aip_xx2/gnss.launch.xml deleted file mode 100644 index 72c636b291..0000000000 --- a/sensing_launch/launch/aip_xx2/gnss.launch.xml +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx2/imu.launch.xml b/sensing_launch/launch/aip_xx2/imu.launch.xml deleted file mode 100644 index 219822bed1..0000000000 --- a/sensing_launch/launch/aip_xx2/imu.launch.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx2/lidar.launch.xml b/sensing_launch/launch/aip_xx2/lidar.launch.xml deleted file mode 100644 index 6b764863f1..0000000000 --- a/sensing_launch/launch/aip_xx2/lidar.launch.xml +++ /dev/null @@ -1,56 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py deleted file mode 100644 index 0485ff3378..0000000000 --- a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py +++ /dev/null @@ -1,193 +0,0 @@ - -# 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.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode -import yaml - - -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', - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - 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'], - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - # 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, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - 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, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - # 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, - ], - output='screen', - ) - - # 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(): - - 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') - add_launch_arg('use_multithread', 'False') - add_launch_arg('use_intra_process', 'False') - - set_container_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container', - condition=UnlessCondition(LaunchConfiguration('use_multithread')) - ) - - set_container_mt_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container_mt', - condition=IfCondition(LaunchConfiguration('use_multithread')) - ) - - return launch.LaunchDescription(launch_arguments + - [set_container_executable, - set_container_mt_executable] + - [OpaqueFunction(function=launch_setup)]) From bcf2476b14403978fcf4c55ce3481a7da0ee8d63 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Fri, 8 Oct 2021 10:42:19 +0900 Subject: [PATCH 246/851] Bump streetsidesoftware/cspell-action from 1.3.3 to 1.3.4 (#447) Bumps [streetsidesoftware/cspell-action](https://github.com/streetsidesoftware/cspell-action) from 1.3.3 to 1.3.4. - [Release notes](https://github.com/streetsidesoftware/cspell-action/releases) - [Changelog](https://github.com/streetsidesoftware/cspell-action/blob/main/CHANGELOG.md) - [Commits](https://github.com/streetsidesoftware/cspell-action/compare/v1.3.3...v1.3.4) --- updated-dependencies: - dependency-name: streetsidesoftware/cspell-action dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/spell_check_pr.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/spell_check_pr.yml b/.github/workflows/spell_check_pr.yml index 484a0e9447..f3ae13deea 100644 --- a/.github/workflows/spell_check_pr.yml +++ b/.github/workflows/spell_check_pr.yml @@ -16,6 +16,6 @@ jobs: --output .github/workflows/.cspell.json \ https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json - - uses: streetsidesoftware/cspell-action@v1.3.3 + - uses: streetsidesoftware/cspell-action@v1.3.4 with: config: ".github/workflows/.cspell.json" From f54a4a8d77e5c163ae87a687470d2f72f17cc57a Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Fri, 8 Oct 2021 14:25:21 +0900 Subject: [PATCH 247/851] Add respawn for ublox (#449) Signed-off-by: wep21 --- sensing_launch/launch/aip_customized/gnss.launch.xml | 2 +- sensing_launch/launch/aip_s1/gnss.launch.xml | 2 +- sensing_launch/launch/aip_x1/gnss.launch.xml | 2 +- sensing_launch/launch/aip_x2/gnss.launch.xml | 2 +- sensing_launch/launch/aip_xx1/gnss.launch.xml | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/sensing_launch/launch/aip_customized/gnss.launch.xml b/sensing_launch/launch/aip_customized/gnss.launch.xml index 72c636b291..5f2b1a29e3 100644 --- a/sensing_launch/launch/aip_customized/gnss.launch.xml +++ b/sensing_launch/launch/aip_customized/gnss.launch.xml @@ -7,7 +7,7 @@ - + diff --git a/sensing_launch/launch/aip_s1/gnss.launch.xml b/sensing_launch/launch/aip_s1/gnss.launch.xml index 72c636b291..5f2b1a29e3 100644 --- a/sensing_launch/launch/aip_s1/gnss.launch.xml +++ b/sensing_launch/launch/aip_s1/gnss.launch.xml @@ -7,7 +7,7 @@ - + diff --git a/sensing_launch/launch/aip_x1/gnss.launch.xml b/sensing_launch/launch/aip_x1/gnss.launch.xml index 2db11f1608..a388e05f43 100644 --- a/sensing_launch/launch/aip_x1/gnss.launch.xml +++ b/sensing_launch/launch/aip_x1/gnss.launch.xml @@ -8,7 +8,7 @@ - + diff --git a/sensing_launch/launch/aip_x2/gnss.launch.xml b/sensing_launch/launch/aip_x2/gnss.launch.xml index 72c636b291..5f2b1a29e3 100644 --- a/sensing_launch/launch/aip_x2/gnss.launch.xml +++ b/sensing_launch/launch/aip_x2/gnss.launch.xml @@ -7,7 +7,7 @@ - + diff --git a/sensing_launch/launch/aip_xx1/gnss.launch.xml b/sensing_launch/launch/aip_xx1/gnss.launch.xml index f8d7331f3e..5370dbeb65 100644 --- a/sensing_launch/launch/aip_xx1/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx1/gnss.launch.xml @@ -15,7 +15,7 @@ - + From 6b26de6199cf059489172d112d3a48713632b54e Mon Sep 17 00:00:00 2001 From: "autoware-iv-sync-ci[bot]" <87871706+autoware-iv-sync-ci[bot]@users.noreply.github.com> Date: Mon, 11 Oct 2021 10:53:08 +0900 Subject: [PATCH 248/851] Auto-update pre-commit hooks (#429) * Auto-update pre-commit hooks * Update update-pre-commit.yml Co-authored-by: KeisukeShima Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .github/workflows/update-pre-commit.yml | 2 +- .pre-commit-config.yaml | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/update-pre-commit.yml b/.github/workflows/update-pre-commit.yml index f18fd62386..d4a2f277d6 100644 --- a/.github/workflows/update-pre-commit.yml +++ b/.github/workflows/update-pre-commit.yml @@ -2,7 +2,7 @@ name: Update pre-commit on: schedule: - - cron: "0 19 * * *" # run at 4 AM JST + - cron: "0 19 * * 0" # run at 4 AM JST on Sundays workflow_dispatch: jobs: diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index c494a64fdd..63358e031a 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -34,7 +34,7 @@ repos: args: [--markdown-linebreak-ext=md] - repo: https://github.com/igorshubovych/markdownlint-cli - rev: v0.28.1 + rev: v0.29.0 hooks: - id: markdownlint args: ["-c", ".markdownlint.yaml", "--fix"] @@ -46,13 +46,13 @@ repos: exclude: "(.rviz|.param.yaml|traffic_light_camera.yaml)" - repo: https://github.com/tier4/pre-commit-hooks-ros - rev: v0.2.0 + rev: v0.3.0 hooks: - id: prettier-package-xml - id: sort-package-xml - repo: https://github.com/gruntwork-io/pre-commit - rev: v0.1.15 + rev: v0.1.16 hooks: - id: shellcheck From 848d675a0250b76b2ccafa4fa632d85e58f62807 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Tue, 12 Oct 2021 10:59:23 +0900 Subject: [PATCH 249/851] delete aip and modify package settings (#434) --- sensing_launch/CMakeLists.txt | 1 - sensing_launch/data/traffic_light_camera.yaml | 20 - .../launch/aip_customized/camera.launch.xml | 24 -- .../launch/aip_customized/gnss.launch.xml | 31 -- .../launch/aip_customized/imu.launch.xml | 24 -- .../launch/aip_customized/lidar.launch.xml | 56 --- .../pointcloud_preprocessor.launch.py | 193 --------- .../launch/aip_s1/camera.launch.xml | 24 -- sensing_launch/launch/aip_s1/gnss.launch.xml | 31 -- sensing_launch/launch/aip_s1/imu.launch.xml | 24 -- sensing_launch/launch/aip_s1/lidar.launch.xml | 56 --- .../aip_s1/pointcloud_preprocessor.launch.py | 191 --------- .../launch/aip_x1/camera.launch.xml | 23 -- sensing_launch/launch/aip_x1/gnss.launch.xml | 32 -- sensing_launch/launch/aip_x1/imu.launch.xml | 16 - sensing_launch/launch/aip_x1/lidar.launch.xml | 68 ---- .../aip_x1/pointcloud_preprocessor.launch.py | 378 ------------------ .../launch/aip_x2/camera.launch.xml | 24 -- sensing_launch/launch/aip_x2/gnss.launch.xml | 31 -- sensing_launch/launch/aip_x2/imu.launch.xml | 24 -- sensing_launch/launch/aip_x2/lidar.launch.xml | 56 --- .../aip_x2/pointcloud_preprocessor.launch.py | 182 --------- .../launch/aip_xx1/camera.launch.xml | 27 -- sensing_launch/launch/aip_xx1/gnss.launch.xml | 45 --- sensing_launch/launch/aip_xx1/imu.launch.xml | 24 -- .../launch/aip_xx1/lidar.launch.xml | 103 ----- .../aip_xx1/pointcloud_preprocessor.launch.py | 193 --------- sensing_launch/launch/livox_horizon.launch.py | 170 -------- sensing_launch/launch/sensing.launch.xml | 21 +- .../launch/velodyne_VLP16.launch.xml | 43 -- .../launch/velodyne_VLP32C.launch.xml | 43 -- .../launch/velodyne_VLS128.launch.xml | 43 -- .../launch/velodyne_node_container.launch.py | 242 ----------- sensing_launch/package.xml | 13 - 34 files changed, 4 insertions(+), 2472 deletions(-) delete mode 100644 sensing_launch/data/traffic_light_camera.yaml delete mode 100644 sensing_launch/launch/aip_customized/camera.launch.xml delete mode 100644 sensing_launch/launch/aip_customized/gnss.launch.xml delete mode 100644 sensing_launch/launch/aip_customized/imu.launch.xml delete mode 100644 sensing_launch/launch/aip_customized/lidar.launch.xml delete mode 100644 sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py delete mode 100644 sensing_launch/launch/aip_s1/camera.launch.xml delete mode 100644 sensing_launch/launch/aip_s1/gnss.launch.xml delete mode 100644 sensing_launch/launch/aip_s1/imu.launch.xml delete mode 100644 sensing_launch/launch/aip_s1/lidar.launch.xml delete mode 100644 sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py delete mode 100644 sensing_launch/launch/aip_x1/camera.launch.xml delete mode 100644 sensing_launch/launch/aip_x1/gnss.launch.xml delete mode 100644 sensing_launch/launch/aip_x1/imu.launch.xml delete mode 100644 sensing_launch/launch/aip_x1/lidar.launch.xml delete mode 100644 sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py delete mode 100644 sensing_launch/launch/aip_x2/camera.launch.xml delete mode 100644 sensing_launch/launch/aip_x2/gnss.launch.xml delete mode 100644 sensing_launch/launch/aip_x2/imu.launch.xml delete mode 100644 sensing_launch/launch/aip_x2/lidar.launch.xml delete mode 100644 sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py delete mode 100644 sensing_launch/launch/aip_xx1/camera.launch.xml delete mode 100644 sensing_launch/launch/aip_xx1/gnss.launch.xml delete mode 100644 sensing_launch/launch/aip_xx1/imu.launch.xml delete mode 100644 sensing_launch/launch/aip_xx1/lidar.launch.xml delete mode 100644 sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py delete mode 100644 sensing_launch/launch/livox_horizon.launch.py delete mode 100644 sensing_launch/launch/velodyne_VLP16.launch.xml delete mode 100644 sensing_launch/launch/velodyne_VLP32C.launch.xml delete mode 100644 sensing_launch/launch/velodyne_VLS128.launch.xml delete mode 100644 sensing_launch/launch/velodyne_node_container.launch.py diff --git a/sensing_launch/CMakeLists.txt b/sensing_launch/CMakeLists.txt index 036e5b89af..408ba2fe4a 100644 --- a/sensing_launch/CMakeLists.txt +++ b/sensing_launch/CMakeLists.txt @@ -11,5 +11,4 @@ endif() ament_auto_package(INSTALL_TO_SHARE launch - data ) diff --git a/sensing_launch/data/traffic_light_camera.yaml b/sensing_launch/data/traffic_light_camera.yaml deleted file mode 100644 index 458ad17ca2..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] diff --git a/sensing_launch/launch/aip_customized/camera.launch.xml b/sensing_launch/launch/aip_customized/camera.launch.xml deleted file mode 100644 index 617d5fbb68..0000000000 --- a/sensing_launch/launch/aip_customized/camera.launch.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_customized/gnss.launch.xml b/sensing_launch/launch/aip_customized/gnss.launch.xml deleted file mode 100644 index 5f2b1a29e3..0000000000 --- a/sensing_launch/launch/aip_customized/gnss.launch.xml +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_customized/imu.launch.xml b/sensing_launch/launch/aip_customized/imu.launch.xml deleted file mode 100644 index c7305b6924..0000000000 --- a/sensing_launch/launch/aip_customized/imu.launch.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_customized/lidar.launch.xml b/sensing_launch/launch/aip_customized/lidar.launch.xml deleted file mode 100644 index 93d040ce3b..0000000000 --- a/sensing_launch/launch/aip_customized/lidar.launch.xml +++ /dev/null @@ -1,56 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py deleted file mode 100644 index a9e3b03e55..0000000000 --- a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py +++ /dev/null @@ -1,193 +0,0 @@ - -# 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.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode -import yaml - - -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': LaunchConfiguration('base_frame'), - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - passthrough_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PassThroughFilterComponent', - name='passthrough_filter', - remappings=[ - ('input', 'top/outlier_filtered/pointcloud'), - ('output', 'concatenated/pointcloud'), - ], - parameters=[{ - 'output_frame': LaunchConfiguration('base_frame'), - 'min_z': vehicle_info['min_height_offset'], - 'max_z': vehicle_info['max_height_offset'], - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - # 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, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - 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, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - # set container to run all required components in the same process - container = ComposableNodeContainer( - name='pointcloud_preprocessor_container', - namespace='pointcloud_preprocessor', - package='rclcpp_components', - executable=LaunchConfiguration('container_executable'), - composable_node_descriptions=[ - cropbox_component, - ground_component, - ], - output='screen', - ) - - # load concat or passthrough filter - concat_loader = LoadComposableNodes( - composable_node_descriptions=[concat_component], - target_container=container, - condition=IfCondition(LaunchConfiguration('use_concat_filter')), - ) - - passthrough_loader = LoadComposableNodes( - composable_node_descriptions=[passthrough_component], - target_container=container, - condition=UnlessCondition(LaunchConfiguration('use_concat_filter')), - ) - - return [container, concat_loader, passthrough_loader] - - -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('use_concat_filter', 'use_concat_filter') - add_launch_arg('vehicle_param_file') - add_launch_arg('use_multithread', 'False') - add_launch_arg('use_intra_process', 'False') - - set_container_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container', - condition=UnlessCondition(LaunchConfiguration('use_multithread')) - ) - - set_container_mt_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container_mt', - condition=IfCondition(LaunchConfiguration('use_multithread')) - ) - - return launch.LaunchDescription(launch_arguments + - [set_container_executable, - set_container_mt_executable] + - [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_s1/camera.launch.xml b/sensing_launch/launch/aip_s1/camera.launch.xml deleted file mode 100644 index 617d5fbb68..0000000000 --- a/sensing_launch/launch/aip_s1/camera.launch.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_s1/gnss.launch.xml b/sensing_launch/launch/aip_s1/gnss.launch.xml deleted file mode 100644 index 5f2b1a29e3..0000000000 --- a/sensing_launch/launch/aip_s1/gnss.launch.xml +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_s1/imu.launch.xml b/sensing_launch/launch/aip_s1/imu.launch.xml deleted file mode 100644 index e32d7dc97c..0000000000 --- a/sensing_launch/launch/aip_s1/imu.launch.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_s1/lidar.launch.xml b/sensing_launch/launch/aip_s1/lidar.launch.xml deleted file mode 100644 index f87e7d1538..0000000000 --- a/sensing_launch/launch/aip_s1/lidar.launch.xml +++ /dev/null @@ -1,56 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py deleted file mode 100644 index 438fee810b..0000000000 --- a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py +++ /dev/null @@ -1,191 +0,0 @@ -# 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.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode -import yaml - - -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': LaunchConfiguration('base_frame'), - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - passthrough_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PassThroughFilterComponent', - name='passthrough_filter', - remappings=[ - ('input', 'top/outlier_filtered/pointcloud'), - ('output', 'concatenated/pointcloud'), - ], - parameters=[{ - 'output_frame': LaunchConfiguration('base_frame'), - 'min_z': vehicle_info['min_height_offset'], - 'max_z': vehicle_info['max_height_offset'], - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - # 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, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - 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, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - # set container to run all required components in the same process - container = ComposableNodeContainer( - name='pointcloud_preprocessor_container', - namespace='pointcloud_preprocessor', - package='rclcpp_components', - executable=LaunchConfiguration('container_executable'), - composable_node_descriptions=[ - cropbox_component, - ground_component, - ], - output='screen', - ) - - # load concat or passthrough filter - concat_loader = LoadComposableNodes( - composable_node_descriptions=[concat_component], - target_container=container, - condition=IfCondition(LaunchConfiguration('use_concat_filter')), - ) - - passthrough_loader = LoadComposableNodes( - composable_node_descriptions=[passthrough_component], - target_container=container, - condition=UnlessCondition(LaunchConfiguration('use_concat_filter')), - ) - - return [container, concat_loader, passthrough_loader] - - -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('use_concat_filter', 'use_concat_filter') - add_launch_arg('vehicle_param_file') - add_launch_arg('use_multithread', 'False') - add_launch_arg('use_intra_process', 'False') - - set_container_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container', - condition=UnlessCondition(LaunchConfiguration('use_multithread')) - ) - - set_container_mt_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container_mt', - condition=IfCondition(LaunchConfiguration('use_multithread')) - ) - - return launch.LaunchDescription(launch_arguments + - [set_container_executable, - set_container_mt_executable] + - [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_x1/camera.launch.xml b/sensing_launch/launch/aip_x1/camera.launch.xml deleted file mode 100644 index 525b5285fc..0000000000 --- a/sensing_launch/launch/aip_x1/camera.launch.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x1/gnss.launch.xml b/sensing_launch/launch/aip_x1/gnss.launch.xml deleted file mode 100644 index a388e05f43..0000000000 --- a/sensing_launch/launch/aip_x1/gnss.launch.xml +++ /dev/null @@ -1,32 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x1/imu.launch.xml b/sensing_launch/launch/aip_x1/imu.launch.xml deleted file mode 100644 index 0771709bda..0000000000 --- a/sensing_launch/launch/aip_x1/imu.launch.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x1/lidar.launch.xml b/sensing_launch/launch/aip_x1/lidar.launch.xml deleted file mode 100644 index fa1212a7aa..0000000000 --- a/sensing_launch/launch/aip_x1/lidar.launch.xml +++ /dev/null @@ -1,68 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py deleted file mode 100644 index e577f912ae..0000000000 --- a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py +++ /dev/null @@ -1,378 +0,0 @@ - -# 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.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode -import yaml - - -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': LaunchConfiguration('base_frame'), - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - # 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': LaunchConfiguration('base_frame'), - 'min_z': vehicle_info['min_height_offset'], - 'max_z': vehicle_info['max_height_offset'], - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - # 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': -0.5, - 'max_z': vehicle_info['max_height_offset'], - 'negative': False, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - ray_ground_filter_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::RayGroundFilterComponent', - name='ray_ground_filter', - remappings=[ - ('input', 'measurement_range_cropped/pointcloud'), - ('output', 'rough/no_ground/pointcloud'), - ], - parameters=[{ - 'initial_max_slope': 10.0, - 'general_max_slope': 10.0, - 'local_max_slope': 10.0, - 'min_height_threshold': 0.3, - 'radial_divider_angle': 1.0, - 'concentric_divider_distance': 0.0, - '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'], - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - short_height_obstacle_detection_area_filter_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::CropBoxFilterComponent', - name='short_height_obstacle_detection_area_filter', - remappings=[ - ('input', 'front_center/mirror_cropped/pointcloud'), - ('output', 'short_height_obstacle_detection_area/pointcloud'), - ], - parameters=[{ - 'input_frame': LaunchConfiguration('base_frame'), - 'output_frame': LaunchConfiguration('base_frame'), - 'min_x': 0.0, - 'max_x': 15.6, # max_x: 14.0m + base_link2livox_front_center distance 1.6m - 'min_y': -4.0, - 'max_y': 4.0, - 'min_z': -0.5, - 'max_z': 0.5, - 'negative': False, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - vector_map_filter_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::Lanelet2MapFilterComponent', - name='vector_map_filter', - remappings=[ - ('input/pointcloud', 'short_height_obstacle_detection_area/pointcloud'), - ('input/vector_map', '/map/vector_map'), - ('output', 'vector_map_filtered/pointcloud'), - ], - parameters=[{ - 'voxel_size_x': 0.25, - 'voxel_size_y': 0.25, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - ransac_ground_filter_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::RANSACGroundFilterComponent', - name='ransac_ground_filter', - remappings=[ - ('input', 'vector_map_filtered/pointcloud'), - ('output', 'short_height/no_ground/pointcloud'), - ], - parameters=[{ - 'outlier_threshold': 0.1, - 'min_points': 400, - 'min_inliers': 200, - 'max_iterations': 50, - 'height_threshold': 0.12, - 'plane_slope_threshold': 10.0, - 'voxel_size_x': 0.2, - 'voxel_size_y': 0.2, - 'voxel_size_z': 0.2, - 'debug': False, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - concat_no_ground_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', - name='concatenate_no_ground_data', - remappings=[('output', 'no_ground/concatenated/pointcloud')], - parameters=[{ - 'input_topics': ['/sensing/lidar/rough/no_ground/pointcloud', - '/sensing/lidar/short_height/no_ground/pointcloud'], - 'output_frame': LaunchConfiguration('base_frame'), - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - voxel_grid_filter_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::VoxelGridDownsampleFilterComponent', - name='voxel_grid_filter', - remappings=[ - ('input', 'no_ground/concatenated/pointcloud'), - ('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, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - 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, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - voxel_grid_outlier_filter_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::VoxelGridOutlierFilterComponent', - name='voxel_grid_outlier_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, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - relay_component = ComposableNode( - package='topic_tools', - plugin='topic_tools::RelayNode', - name='relay', - parameters=[{ - 'input_topic': '/sensing/lidar/top/outlier_filtered/pointcloud', - 'output_topic': '/sensing/lidar/pointcloud', - 'type': 'sensor_msgs/msg/PointCloud2', - 'history': 'keep_last', - 'depth': 5, - 'reliability': 'best_effort', - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - # set container to run all required components in the same process - container = ComposableNodeContainer( - name='pointcloud_preprocessor_container', - namespace='pointcloud_preprocessor', - package='rclcpp_components', - executable=LaunchConfiguration('container_executable'), - composable_node_descriptions=[ - cropbox_component, - ray_ground_filter_component, - short_height_obstacle_detection_area_filter_component, - vector_map_filter_component, - ransac_ground_filter_component, - concat_no_ground_component, - voxel_grid_filter_component, - relay_component, - ], - output='screen', - ) - - # 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(): - - 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', 'true') - add_launch_arg('use_radius_search', 'true') - add_launch_arg('vehicle_param_file') - add_launch_arg('use_multithread', 'False') - add_launch_arg('use_intra_process', 'False') - - set_container_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container', - condition=UnlessCondition(LaunchConfiguration('use_multithread')) - ) - - set_container_mt_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container_mt', - condition=IfCondition(LaunchConfiguration('use_multithread')) - ) - - return launch.LaunchDescription(launch_arguments + - [set_container_executable, - set_container_mt_executable] + - [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_x2/camera.launch.xml b/sensing_launch/launch/aip_x2/camera.launch.xml deleted file mode 100644 index 617d5fbb68..0000000000 --- a/sensing_launch/launch/aip_x2/camera.launch.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x2/gnss.launch.xml b/sensing_launch/launch/aip_x2/gnss.launch.xml deleted file mode 100644 index 5f2b1a29e3..0000000000 --- a/sensing_launch/launch/aip_x2/gnss.launch.xml +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x2/imu.launch.xml b/sensing_launch/launch/aip_x2/imu.launch.xml deleted file mode 100644 index c22b05172a..0000000000 --- a/sensing_launch/launch/aip_x2/imu.launch.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x2/lidar.launch.xml b/sensing_launch/launch/aip_x2/lidar.launch.xml deleted file mode 100644 index ecaf554a04..0000000000 --- a/sensing_launch/launch/aip_x2/lidar.launch.xml +++ /dev/null @@ -1,56 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py deleted file mode 100644 index 2da76720bf..0000000000 --- a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py +++ /dev/null @@ -1,182 +0,0 @@ - -# 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.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.descriptions import ComposableNode -import yaml - - -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', - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - 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'], - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - # 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, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - 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, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - # set container to run all required components in the same process - container = ComposableNodeContainer( - name='pointcloud_preprocessor_container', - namespace='pointcloud_preprocessor', - package='rclcpp_components', - executable=LaunchConfiguration('container_executable'), - composable_node_descriptions=[ - concat_component, - cropbox_component, - ground_component, - ], - output='screen', - ) - - 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('use_concat_filter', 'use_concat_filter') - add_launch_arg('vehicle_param_file') - add_launch_arg('use_multithread', 'False') - add_launch_arg('use_intra_process', 'False') - - set_container_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container', - condition=UnlessCondition(LaunchConfiguration('use_multithread')) - ) - - set_container_mt_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container_mt', - condition=IfCondition(LaunchConfiguration('use_multithread')) - ) - - return launch.LaunchDescription(launch_arguments + - [set_container_executable, - set_container_mt_executable] + - [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_xx1/camera.launch.xml b/sensing_launch/launch/aip_xx1/camera.launch.xml deleted file mode 100644 index 09cfea332e..0000000000 --- a/sensing_launch/launch/aip_xx1/camera.launch.xml +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx1/gnss.launch.xml b/sensing_launch/launch/aip_xx1/gnss.launch.xml deleted file mode 100644 index 5370dbeb65..0000000000 --- a/sensing_launch/launch/aip_xx1/gnss.launch.xml +++ /dev/null @@ -1,45 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx1/imu.launch.xml b/sensing_launch/launch/aip_xx1/imu.launch.xml deleted file mode 100644 index 705756e703..0000000000 --- a/sensing_launch/launch/aip_xx1/imu.launch.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx1/lidar.launch.xml b/sensing_launch/launch/aip_xx1/lidar.launch.xml deleted file mode 100644 index 2300103af5..0000000000 --- a/sensing_launch/launch/aip_xx1/lidar.launch.xml +++ /dev/null @@ -1,103 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py deleted file mode 100644 index a9e3b03e55..0000000000 --- a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py +++ /dev/null @@ -1,193 +0,0 @@ - -# 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.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode -import yaml - - -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': LaunchConfiguration('base_frame'), - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - passthrough_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PassThroughFilterComponent', - name='passthrough_filter', - remappings=[ - ('input', 'top/outlier_filtered/pointcloud'), - ('output', 'concatenated/pointcloud'), - ], - parameters=[{ - 'output_frame': LaunchConfiguration('base_frame'), - 'min_z': vehicle_info['min_height_offset'], - 'max_z': vehicle_info['max_height_offset'], - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - # 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, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - 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, - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - - # set container to run all required components in the same process - container = ComposableNodeContainer( - name='pointcloud_preprocessor_container', - namespace='pointcloud_preprocessor', - package='rclcpp_components', - executable=LaunchConfiguration('container_executable'), - composable_node_descriptions=[ - cropbox_component, - ground_component, - ], - output='screen', - ) - - # load concat or passthrough filter - concat_loader = LoadComposableNodes( - composable_node_descriptions=[concat_component], - target_container=container, - condition=IfCondition(LaunchConfiguration('use_concat_filter')), - ) - - passthrough_loader = LoadComposableNodes( - composable_node_descriptions=[passthrough_component], - target_container=container, - condition=UnlessCondition(LaunchConfiguration('use_concat_filter')), - ) - - return [container, concat_loader, passthrough_loader] - - -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('use_concat_filter', 'use_concat_filter') - add_launch_arg('vehicle_param_file') - add_launch_arg('use_multithread', 'False') - add_launch_arg('use_intra_process', 'False') - - set_container_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container', - condition=UnlessCondition(LaunchConfiguration('use_multithread')) - ) - - set_container_mt_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container_mt', - condition=IfCondition(LaunchConfiguration('use_multithread')) - ) - - return launch.LaunchDescription(launch_arguments + - [set_container_executable, - set_container_mt_executable] + - [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/livox_horizon.launch.py b/sensing_launch/launch/livox_horizon.launch.py deleted file mode 100644 index af5a5560ee..0000000000 --- a/sensing_launch/launch/livox_horizon.launch.py +++ /dev/null @@ -1,170 +0,0 @@ - -# 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 - -from ament_index_python.packages import get_package_share_directory -import launch -from launch.actions import DeclareLaunchArgument -from launch.actions import OpaqueFunction -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode -import yaml - - -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) - - bd_code_param_path = LaunchConfiguration('bd_code_param_path').perform(context) - with open(bd_code_param_path, 'r') as f: - bd_code_param = yaml.safe_load(f)['/**']['ros__parameters'] - - # livox driver - livox_driver_component = ComposableNode( - package='livox_ros2_driver', - plugin='livox_ros::LivoxDriver', - name='livox_driver', - parameters=[ - { - 'xfe_format': LaunchConfiguration('xfe_format'), - 'multi_topic': LaunchConfiguration('multi_topic'), - 'data_src': LaunchConfiguration('data_src'), - 'publish_freq': LaunchConfiguration('publish_freq'), - 'output_data_type': LaunchConfiguration('output_type'), - 'lvx_file_path': LaunchConfiguration('lvx_file_path'), - 'user_config_path': LaunchConfiguration('user_config_path'), - 'frame_id': LaunchConfiguration('sensor_frame'), - }, - bd_code_param, - ] - ) - - # 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, - }] - ) - - # 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, - }] - ) - - # 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', - ) - - loader = LoadComposableNodes( - composable_node_descriptions=[livox_driver_component], - target_container=container, - condition=launch.conditions.IfCondition(LaunchConfiguration('launch_driver')), - ) - - return [container, loader] - - -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('xfe_format', '0') - add_launch_arg('multi_topic', '0') - add_launch_arg('data_src', '0') - add_launch_arg('publish_freq', '10.0') - add_launch_arg('output_type', '0') - add_launch_arg('lvx_file_path', 'livox_test.lvx') - add_launch_arg('user_config_path', os.path.join(get_package_share_directory( - 'livox_ros2_driver'), 'config/livox_lidar_config.json')) - add_launch_arg('bd_code_param_path') - add_launch_arg('launch_driver') - add_launch_arg('base_frame', 'base_link') - add_launch_arg('sensor_frame', 'livox_frame') - 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 91bc779575..8795835878 100644 --- a/sensing_launch/launch/sensing.launch.xml +++ b/sensing_launch/launch/sensing.launch.xml @@ -5,31 +5,18 @@ + + - - + + - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/velodyne_VLP16.launch.xml b/sensing_launch/launch/velodyne_VLP16.launch.xml deleted file mode 100644 index 61b60884b5..0000000000 --- a/sensing_launch/launch/velodyne_VLP16.launch.xml +++ /dev/null @@ -1,43 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/velodyne_VLP32C.launch.xml b/sensing_launch/launch/velodyne_VLP32C.launch.xml deleted file mode 100644 index 208f9da8ad..0000000000 --- a/sensing_launch/launch/velodyne_VLP32C.launch.xml +++ /dev/null @@ -1,43 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/velodyne_VLS128.launch.xml b/sensing_launch/launch/velodyne_VLS128.launch.xml deleted file mode 100644 index 0820e641b9..0000000000 --- a/sensing_launch/launch/velodyne_VLS128.launch.xml +++ /dev/null @@ -1,43 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/velodyne_node_container.launch.py b/sensing_launch/launch/velodyne_node_container.launch.py deleted file mode 100644 index ae3af1ad00..0000000000 --- a/sensing_launch/launch/velodyne_node_container.launch.py +++ /dev/null @@ -1,242 +0,0 @@ -# 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.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode -import yaml - - -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): - - 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', - 'frame_id', 'scan_phase', - 'view_direction', 'view_width'), - }], - remappings=[('velodyne_points', 'pointcloud_raw'), - ('velodyne_points_ex', 'pointcloud_raw_ex')], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - ) - - cropbox_parameters = create_parameter_dict('input_frame', 'output_frame') - cropbox_parameters['negative'] = True - - 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'), - ], - parameters=[cropbox_parameters], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - ) - - 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'), - ], - parameters=[cropbox_parameters], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - ) - - 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'), - ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - ) - - nodes.append(ComposableNode( - package='pointcloud_preprocessor', - plugin='pointcloud_preprocessor::RingOutlierFilterComponent', - name='ring_outlier_filter', - remappings=[ - ('input', 'rectified/pointcloud_ex'), - ('output', 'outlier_filtered/pointcloud') - ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) - ) - - # 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='velodyne_node_container', - namespace='pointcloud_preprocessor', - package='rclcpp_components', - executable=LaunchConfiguration('container_executable'), - 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', 'scan_phase'), - }], - ) - - # 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 [container, loader] - - -def generate_launch_description(): - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None, description=None): - # a default_value of None is equivalent to not passing that kwarg at all - launch_arguments.append(DeclareLaunchArgument( - name, default_value=default_value, description=description)) - - add_launch_arg('model', description='velodyne model name') - add_launch_arg('launch_driver', 'True', 'do launch driver') - add_launch_arg('calibration', description='path to calibration file') - add_launch_arg('device_ip', '192.168.1.201', 'device ip address') - add_launch_arg('scan_phase', '0.0') - add_launch_arg('base_frame', 'base_link', 'base frame id') - add_launch_arg('container_name', 'velodyne_composable_node_container', 'container name') - add_launch_arg('min_range', description='minimum view range') - add_launch_arg('max_range', description='maximum view range') - add_launch_arg('pcap', '') - add_launch_arg('port', '2368', description='device port number') - 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', 'rotational frequency') - 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', 'velodyne frame id') - add_launch_arg('gps_time', 'False') - add_launch_arg('view_direction', description='the center of lidar angle') - add_launch_arg('view_width', description='lidar angle: 0~6.28 [rad]') - add_launch_arg('input_frame', LaunchConfiguration('base_frame'), 'use for cropbox') - add_launch_arg('output_frame', LaunchConfiguration('base_frame'), 'use for cropbox') - add_launch_arg('vehicle_param_file', description='path to the file of vehicle info yaml') - add_launch_arg('vehicle_mirror_param_file', - description='path to the file of vehicle mirror position yaml') - add_launch_arg('use_multithread', 'False', 'use multithread') - add_launch_arg('use_intra_process', 'False', 'use ROS2 component container communication') - - set_container_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container', - condition=UnlessCondition(LaunchConfiguration('use_multithread')) - ) - - set_container_mt_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container_mt', - condition=IfCondition(LaunchConfiguration('use_multithread')) - ) - - return launch.LaunchDescription(launch_arguments + - [set_container_executable, - set_container_mt_executable] + - [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/package.xml b/sensing_launch/package.xml index 13b7bc9276..f5b0339aeb 100644 --- a/sensing_launch/package.xml +++ b/sensing_launch/package.xml @@ -10,19 +10,6 @@ ament_cmake_auto - gnss_poser - livox_ros2_driver - pointcloud_preprocessor - tamagawa_imu_driver - topic_tools - ublox_gps - usb_cam - usb_cam - velodyne_driver - velodyne_monitor - velodyne_pointcloud - - ament_lint_auto ament_lint_common From 13b83626aff9fb94e8bb84fd525eeee9ef165d80 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 13 Oct 2021 12:31:10 +0900 Subject: [PATCH 250/851] Add polar grid into rviz config (#458) --- 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 6c3fe300b3..8446215039 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -287,6 +287,20 @@ Visualization Manager: Update Interval: 0 Value: true Visual Enabled: true + - Class: rviz_plugins/PolarGridDisplay + Color: 255; 255; 255 + Delta Range: 10 + Enabled: true + Max Alpha: 0.5 + Max Range: 100 + Max Wave Alpha: 0.5 + Min Alpha: 0.01 + Min Wave Alpha: 0.01 + Name: PolarGridDisplay + Reference Frame: base_link + Value: true + Wave Color: 255; 255; 255 + Wave Velocity: 40 - Class: rviz_plugins/MaxVelocity Enabled: true Left: 595 From c4fd7d67e5334e3e119355d7b5263e30324aea49 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Thu, 14 Oct 2021 13:11:51 +0900 Subject: [PATCH 251/851] Add simulator_launch package (#459) * Add simulator_launch package * add argument * fix depend order * add argument * move dummy_perception_publisher * add arg for dummy_perception_publisher * Update simulator_launch/launch/simulator.launch.xml Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .../launch/planning_simulator.launch.xml | 17 +++++++------- autoware_launch/package.xml | 1 + simulator_launch/CMakeLists.txt | 14 ++++++++++++ simulator_launch/README.md | 11 ++++++++++ simulator_launch/launch/simulator.launch.xml | 20 +++++++++++++++++ simulator_launch/package.xml | 22 +++++++++++++++++++ 6 files changed, 76 insertions(+), 9 deletions(-) create mode 100644 simulator_launch/CMakeLists.txt create mode 100644 simulator_launch/README.md create mode 100644 simulator_launch/launch/simulator.launch.xml create mode 100644 simulator_launch/package.xml diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index b0abe9bfaf..1ff00231f2 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -44,15 +44,6 @@ - - - - - - - - - @@ -74,4 +65,12 @@ + + + + + + + + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index c564859851..5ca5f78f72 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -21,6 +21,7 @@ python3-tornado rviz2 sensing_launch + simulator_launch system_launch vehicle_launch diff --git a/simulator_launch/CMakeLists.txt b/simulator_launch/CMakeLists.txt new file mode 100644 index 0000000000..bbabec7ab1 --- /dev/null +++ b/simulator_launch/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 3.5) +project(simulator_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/simulator_launch/README.md b/simulator_launch/README.md new file mode 100644 index 0000000000..4864936a28 --- /dev/null +++ b/simulator_launch/README.md @@ -0,0 +1,11 @@ +# simulator_launch + +## Package Dependencies + +Please see `` in `package.xml`. + +## Usage + +```xml + +``` diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml new file mode 100644 index 0000000000..507a7fd952 --- /dev/null +++ b/simulator_launch/launch/simulator.launch.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/simulator_launch/package.xml b/simulator_launch/package.xml new file mode 100644 index 0000000000..9ef9700a31 --- /dev/null +++ b/simulator_launch/package.xml @@ -0,0 +1,22 @@ + + + + simulator_launch + 0.1.0 + The simulator_launch package + + Keisuke Shima + Apache License 2.0 + + ament_cmake_auto + + dummy_perception_publisher + fault_injection + + ament_lint_auto + ament_lint_common + + + ament_cmake + + From 138004bf0e2b39d20d76d9d6df97346457adf647 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 14 Oct 2021 18:09:53 +0900 Subject: [PATCH 252/851] add sync-upstream-develop (#463) * add sync-upstream-develop * fix base branch * fix typo and style --- .github/workflows/sync-upstream-develop.yml | 77 +++++++++++++++++++++ 1 file changed, 77 insertions(+) create mode 100644 .github/workflows/sync-upstream-develop.yml diff --git a/.github/workflows/sync-upstream-develop.yml b/.github/workflows/sync-upstream-develop.yml new file mode 100644 index 0000000000..b288a0fb16 --- /dev/null +++ b/.github/workflows/sync-upstream-develop.yml @@ -0,0 +1,77 @@ +name: sync upstream develop + +on: + schedule: + - cron: "0 19 * * *" # run at 4 AM JST + workflow_dispatch: + +env: + UPSTREAM_REPO: https://github.com/tier4/autoware_launcher.git + BASE_BRANCH: develop + SYNC_TARGET_BRANCH: develop + SYNC_BRANCH: sync-upstream-develop + +jobs: + sync-upstream: + runs-on: ubuntu-20.04 + + steps: + - name: Checkout repository + uses: actions/checkout@v2 + with: + ref: ${{ env.BASE_BRANCH }} + fetch-depth: 0 + + - name: Generate token + uses: tibdex/github-app-token@v1 + id: generate-token + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.APP_PRIVATE_KEY }} + + - name: Set git config for private repositories + run: | + git config --local --unset-all http.https://github.com/.extraheader || true + git config --global url.https://x-access-token:${{ steps.generate-token.outputs.token }}@github.com.insteadOf 'https://github.com' + + - name: Fetch upstream + run: | + git remote add upstream "${{ env.UPSTREAM_REPO }}" + git fetch -pPtf --all + + # To keep the base branch in "create-pull-request", checkout with "BASE_BRANCH" and reset to "SYNC_TARGET_BRANCH" + - name: Reset to sync target branch + run: | + git reset --hard upstream/${{ env.SYNC_TARGET_BRANCH }} + + - name: Create PR + id: create_pr + uses: peter-evans/create-pull-request@v3 + with: + token: ${{ steps.generate-token.outputs.token }} + commit-message: sync upstream develop + committer: GitHub + author: GitHub + signoff: false + base: ${{ env.BASE_BRANCH }} + branch: ${{ env.SYNC_BRANCH }} + delete-branch: true + title: sync upstream develop + body: | + sync upstream develop + labels: | + sync-upstream-develop + draft: false + + - name: Check outputs + run: | + echo "Pull Request Number - ${{ steps.create_pr.outputs.pull-request-number }}" + echo "Pull Request URL - ${{ steps.create_pr.outputs.pull-request-url }}" + + - name: Enable Auto-merge + if: steps.create_pr.outputs.pull-request-operation == 'created' + uses: peter-evans/enable-pull-request-automerge@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + pull-request-number: ${{ steps.create_pr.outputs.pull-request-number }} + merge-method: merge From 60181a41310ff38acccfb363a02d2cd078dfda45 Mon Sep 17 00:00:00 2001 From: g-ise <53168213+g-ise@users.noreply.github.com> Date: Tue, 19 Oct 2021 16:39:26 +0900 Subject: [PATCH 253/851] Fix: Modify arg in drawio graph for README (perception launch) (#466) Modified True/False and alignment (put to center) of use_empty_dynamic_object_publisher in drawio graph. --- perception_launch/perception_launch.drawio.svg | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/perception_launch/perception_launch.drawio.svg b/perception_launch/perception_launch.drawio.svg index fc19d039ab..49bfa1f700 100644 --- a/perception_launch/perception_launch.drawio.svg +++ b/perception_launch/perception_launch.drawio.svg @@ -1,4 +1,4 @@ - + @@ -36,16 +36,16 @@ -
    +
    - False + True
    - - False + + True @@ -189,13 +189,13 @@
    - True + False
    - True + False From b5d15287944bb6fb47978b27e455da75832f7e53 Mon Sep 17 00:00:00 2001 From: yabuta Date: Wed, 20 Oct 2021 18:50:42 +0900 Subject: [PATCH 254/851] fix parameter name (#470) --- .../launch/mission_planning/mission_planning.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/launch/mission_planning/mission_planning.launch.py b/planning_launch/launch/mission_planning/mission_planning.launch.py index a618e55bed..4f5fb52afd 100644 --- a/planning_launch/launch/mission_planning/mission_planning.launch.py +++ b/planning_launch/launch/mission_planning/mission_planning.launch.py @@ -35,7 +35,7 @@ def generate_launch_description(): ('input/goal_pose', '/planning/mission_planning/goal'), ('input/checkpoint', '/planning/mission_planning/checkpoint'), ('output/route', '/planning/mission_planning/route'), - ('visualization_topic_name', + ('debug/route_marker', '/planning/mission_planning/route_marker'), ], parameters=[ From dff99745092c6fa0aa2a3b32096c3055d4a0cd2f Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Wed, 20 Oct 2021 22:06:12 +0900 Subject: [PATCH 255/851] Fix sync-rc workflow to work if develop branch doesn't exist (#471) Signed-off-by: Kenji Miyake --- .github/workflows/sync-rc.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/sync-rc.yml b/.github/workflows/sync-rc.yml index a45496720d..748d8a2be7 100644 --- a/.github/workflows/sync-rc.yml +++ b/.github/workflows/sync-rc.yml @@ -49,6 +49,8 @@ jobs: function is_main_base() { target_branch="$1" + git rev-parse --quiet --verify origin/develop || return 0 + main_base=$(git merge-base "${target_branch}" origin/main) develop_base=$(git merge-base "${target_branch}" origin/develop) From 61c0b5697dd5f1ba2825bffd9af1dbc639e9466d Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 20 Oct 2021 22:16:01 +0900 Subject: [PATCH 256/851] Feature/autoware api autoware versions (#438) * Add package version API * Fix message type * Modify api name --- .../include/external_api_adaptor.launch.py | 1 + system_launch/launch/system.launch.xml | 3 -- system_launch/package.xml | 1 - system_launch/system_launch.drawio.svg | 28 +------------------ 4 files changed, 2 insertions(+), 31 deletions(-) diff --git a/autoware_api_launch/launch/include/external_api_adaptor.launch.py b/autoware_api_launch/launch/include/external_api_adaptor.launch.py index 6eca7b7553..22e501db81 100644 --- a/autoware_api_launch/launch/include/external_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/external_api_adaptor.launch.py @@ -36,6 +36,7 @@ def generate_launch_description(): _create_api_node('initial_pose', 'InitialPose'), _create_api_node('map', 'Map'), _create_api_node('operator', 'Operator'), + _create_api_node('metadata_packages', 'MetadataPackages'), _create_api_node('route', 'Route'), _create_api_node('service', 'Service'), _create_api_node('start', 'Start'), diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index d21ef0fd45..c332fdb92b 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -50,8 +50,5 @@ - - - diff --git a/system_launch/package.xml b/system_launch/package.xml index 64664d8435..0d79fe7416 100644 --- a/system_launch/package.xml +++ b/system_launch/package.xml @@ -12,7 +12,6 @@ autoware_error_monitor autoware_state_monitor - autoware_version emergency_handler system_monitor diff --git a/system_launch/system_launch.drawio.svg b/system_launch/system_launch.drawio.svg index e203f827e5..b22f005948 100644 --- a/system_launch/system_launch.drawio.svg +++ b/system_launch/system_launch.drawio.svg @@ -1,4 +1,4 @@ - + @@ -396,32 +396,6 @@ - - - - -
    -
    -
    - autoware_version -
    -
    -
    - - package: autoware_version - -
    -
    -
    -
    -
    - - autoware_version... - -
    -
    - - From 6cd7bef7f97da75621aef424fa190a6e9ec3a300 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Tue, 26 Oct 2021 14:47:37 +0900 Subject: [PATCH 257/851] use let variable in system_launch (#473) --- system_launch/launch/system.launch.xml | 33 +++++++++----------------- 1 file changed, 11 insertions(+), 22 deletions(-) diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index c332fdb92b..b51e286361 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -20,30 +20,19 @@ - - - - - - - - - - + + + + + - - - - - - - - - - - - + + + + + + From 59ce97a8c1bffac8c6b58d167233fbc5e60e50a5 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Wed, 27 Oct 2021 23:18:01 +0900 Subject: [PATCH 258/851] add steering angle (#476) --- 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 8446215039..76ea5a1502 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -67,7 +67,7 @@ Visualization Manager: - Class: rviz_common/Group Displays: - Class: rviz_plugins/SteeringAngle - Enabled: false + Enabled: true Left: 128 Length: 256 Name: SteeringAngle From a46e63b77afd5f286bb8659b254c5a352bdbdd16 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Thu, 28 Oct 2021 20:12:54 +0900 Subject: [PATCH 259/851] Move simple_planning_simulator to simulator_launch (#462) * move simple_planning_simulator * add simulation arg to logging_simulator.launch * delete unused argument * add arguments for logging simulation * change default value * update README * add default value to simulator arg * restore vehicle_simulation arg --- autoware_launch/autoware_launch.drawio.svg | 1379 +---------------- autoware_launch/launch/autoware.launch.xml | 1 - .../launch/logging_simulator.launch.xml | 11 +- .../launch/planning_simulator.launch.xml | 6 +- simulator_launch/README.md | 4 + simulator_launch/launch/simulator.launch.xml | 25 +- simulator_launch/package.xml | 1 + simulator_launch/simulator_launch.drawio.svg | 4 + vehicle_launch/README.md | 5 - vehicle_launch/launch/vehicle.launch.xml | 16 +- .../launch/vehicle_interface.launch.xml | 29 - vehicle_launch/package.xml | 1 - vehicle_launch/vehicle_launch.drawio.svg | 446 +----- 13 files changed, 57 insertions(+), 1871 deletions(-) create mode 100644 simulator_launch/simulator_launch.drawio.svg delete mode 100644 vehicle_launch/launch/vehicle_interface.launch.xml diff --git a/autoware_launch/autoware_launch.drawio.svg b/autoware_launch/autoware_launch.drawio.svg index 5c435ce4f4..808a956beb 100644 --- a/autoware_launch/autoware_launch.drawio.svg +++ b/autoware_launch/autoware_launch.drawio.svg @@ -1,1375 +1,4 @@ - - - - - - - -
    -
    -
    - autoware.launch.xml -
    -
    -
    - - package: autoware_launch - -
    -
    -
    -
    -
    - - autoware.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - launch name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - launch name... - -
    -
    - - - - -
    -
    -
    - ex: -
    -
    -
    -
    - - ex: - -
    -
    - - - - -
    -
    -
    - node name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - node name... - -
    -
    - - - - -
    -
    -
    - vehicle_info_launch.py -
    -
    -
    - - package: vehicle_launch - -
    -
    -
    -
    -
    - - vehicle_info_launch.py... - -
    -
    - - - - -
    -
    -
    - vehicle.launch.xml -
    -
    -
    - - package: vehicle_launch - -
    -
    -
    -
    -
    - - vehicle.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - system.launch.xml -
    -
    -
    - - package: system_launch - -
    -
    -
    -
    -
    - - system.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - map.launch.py -
    -
    -
    - - package: map_launch - -
    -
    -
    -
    -
    - - map.launch.py... - -
    -
    - - - - - - -
    -
    -
    - localization.launch.xml -
    -
    -
    - - package: localization_launch - -
    -
    -
    -
    -
    - - localization.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - perception.launch.xml -
    -
    -
    - - package: perception_launch - -
    -
    -
    -
    -
    - - perception.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - planning.launch.xml -
    -
    -
    - - package: planning_launch - -
    -
    -
    -
    -
    - - planning.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - control.launch.py -
    -
    -
    - - package: control_launch - -
    -
    -
    -
    -
    - - control.launch.py... - -
    -
    - - - - - - -
    -
    -
    - awapi_awiv_adapter.launch.xml -
    -
    -
    - - package: control_launch - -
    -
    -
    -
    -
    - - awapi_awiv_adapter.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - autoware_web_controller.launch.xml -
    -
    -
    - - package: control_launch - -
    -
    -
    -
    -
    - - autoware_web_controller.launch.xml... - -
    -
    - - - - -
    -
    -
    - clock_publisher.launch.xml -
    -
    -
    - - package: control_launch - -
    -
    -
    -
    -
    - - clock_publisher.launch.xml... - -
    -
    - - - - - - - - -
    -
    -
    - rviz2 -
    -
    -
    - - package: rviz2 - -
    -
    -
    -
    -
    - - rviz2... - -
    -
    - - - - - - -
    -
    -
    - planning_simulator.xml -
    -
    -
    - - package: autoware_launch - -
    -
    -
    -
    -
    - - planning_simulator.xml... - -
    -
    - - - - - - -
    -
    -
    - vehicle_info_launch.py -
    -
    -
    - - package: vehicle_launch - -
    -
    -
    -
    -
    - - vehicle_info_launch.py... - -
    -
    - - - - -
    -
    -
    - vehicle.launch.xml -
    -
    -
    - - package: vehicle_launch - -
    -
    -
    -
    -
    - - vehicle.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - system.launch.xml -
    -
    -
    - - package: system_launch - -
    -
    -
    -
    -
    - - system.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - map.launch.py -
    -
    -
    - - package: map_launch - -
    -
    -
    -
    -
    - - map.launch.py... - -
    -
    - - - - - - - - -
    -
    -
    - planning.launch.xml -
    -
    -
    - - package: planning_launch - -
    -
    -
    -
    -
    - - planning.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - control.launch.py -
    -
    -
    - - package: control_launch - -
    -
    -
    -
    -
    - - control.launch.py... - -
    -
    - - - - - - -
    -
    -
    - awapi_awiv_adapter.launch.xml -
    -
    -
    - - package: control_launch - -
    -
    -
    -
    -
    - - awapi_awiv_adapter.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - autoware_web_controller.launch.xml -
    -
    -
    - - package: control_launch - -
    -
    -
    -
    -
    - - autoware_web_controller.launch.xml... - -
    -
    - - - - -
    -
    -
    - clock_publisher.launch.xml -
    -
    -
    - - package: control_launch - -
    -
    -
    -
    -
    - - clock_publisher.launch.xml... - -
    -
    - - - - - - - - -
    -
    -
    - rviz2 -
    -
    -
    - - package: rviz2 - -
    -
    -
    -
    -
    - - rviz2... - -
    -
    - - - - - - -
    -
    -
    - $(var scenario_simulation) -
    -
    -
    -
    - - $(var scenario_simulation) - -
    -
    - - - - - -
    -
    -
    - False -
    -
    -
    -
    - - False - -
    -
    - - - - -
    -
    -
    - dummy_perception_publisher.launch.xml -
    -
    -
    - - package: dummy_perception_publisher - -
    -
    -
    -
    -
    - - dummy_perception_publisher.launch.xml... - -
    -
    - - - - -
    -
    -
    - logging_simulator.launch.xml -
    -
    -
    - - package: autoware_launch - -
    -
    -
    -
    -
    - - logging_simulator.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - vehicle_info_launch.py -
    -
    -
    - - package: vehicle_launch - -
    -
    -
    -
    -
    - - vehicle_info_launch.py... - -
    -
    - - - - -
    -
    -
    - vehicle_description.launch.xml -
    -
    -
    - - package: vehicle_launch - -
    -
    -
    -
    -
    - - vehicle_description.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - system.launch.xml -
    -
    -
    - - package: system_launch - -
    -
    -
    -
    -
    - - system.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - map.launch.py -
    -
    -
    - - package: map_launch - -
    -
    -
    -
    -
    - - map.launch.py... - -
    -
    - - - - - - - - -
    -
    -
    - perception.launch.xml -
    -
    -
    - - package: perception_launch - -
    -
    -
    -
    -
    - - perception.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - planning.launch.xml -
    -
    -
    - - package: planning_launch - -
    -
    -
    -
    -
    - - planning.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - control.launch.py -
    -
    -
    - - package: control_launch - -
    -
    -
    -
    -
    - - control.launch.py... - -
    -
    - - - - - - -
    -
    -
    - autoware_web_controller.launch.xml -
    -
    -
    - - package: control_launch - -
    -
    -
    -
    -
    - - autoware_web_controller.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - rviz2 -
    -
    -
    - - package: rviz2 - -
    -
    -
    -
    -
    - - rviz2... - -
    -
    - - - - - - -
    -
    -
    - $(var vehicle) -
    -
    -
    -
    - - $(var vehicle) - -
    -
    - - - - - -
    -
    -
    - True -
    -
    -
    -
    - - True - -
    -
    - - - - -
    -
    -
    - $(var system) -
    -
    -
    -
    - - $(var system) - -
    -
    - - - - - -
    -
    -
    - True -
    -
    -
    -
    - - True - -
    -
    - - - - -
    -
    -
    - $(var map) -
    -
    -
    -
    - - $(var map) - -
    -
    - - - - - -
    -
    -
    - True -
    -
    -
    -
    - - True - -
    -
    - - - - -
    -
    -
    - sensing.launch.xml -
    -
    -
    - - package: sensing_launch - -
    -
    -
    -
    -
    - - sensing.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - sensing.launch.xml -
    -
    -
    - - package: sensing_launch - -
    -
    -
    -
    -
    - - sensing.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - $(var sensing) -
    -
    -
    -
    - - $(var sensing) - -
    -
    - - - - - -
    -
    -
    - True -
    -
    -
    -
    - - True - -
    -
    - - - - -
    -
    -
    - localization.launch.xml -
    -
    -
    - - package: localization_launch - -
    -
    -
    -
    -
    - - localization.launch.xml... - -
    -
    - - - - -
    -
    -
    - $(var localization) -
    -
    -
    -
    - - $(var localization) - -
    -
    - - - - - -
    -
    -
    - True -
    -
    -
    -
    - - True - -
    -
    - - - - -
    -
    -
    - $(var perception) -
    -
    -
    -
    - - $(var perception) - -
    -
    - - - - - -
    -
    -
    - True -
    -
    -
    -
    - - True - -
    -
    - - - - -
    -
    -
    - $(var planning) -
    -
    -
    -
    - - $(var planning) - -
    -
    - - - - - -
    -
    -
    - True -
    -
    -
    -
    - - True - -
    -
    - - - - -
    -
    -
    - $(var control) -
    -
    -
    -
    - - $(var control) - -
    -
    - - - - - -
    -
    -
    - True -
    -
    -
    -
    - - True - -
    -
    -
    - - - - - Viewer does not support full SVG 1.1 - - - -
    \ No newline at end of file + + + +
    autoware.launch.xml

    package: autoware_launch
    autoware.launch.xml...
    launch name

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

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

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

    package: vehicle_launch
    vehicle.launch.xml...
    system.launch.xml

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

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

    package: localization_launch
    localization.launch.xml...
    perception.launch.xml

    package: perception_launch
    perception.launch.xml...
    planning.launch.xml

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

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

    package: control_launch
    awapi_awiv_adapter.launch.xml...
    autoware_web_controller.launch.xml

    package: control_launch
    autoware_web_controller.launch.xml...
    clock_publisher.launch.xml

    package: control_launch
    clock_publisher.launch.xml...
    rviz2

    package: rviz2
    rviz2...
    planning_simulator.xml

    package: autoware_launch
    planning_simulator.xml...
    vehicle_info_launch.py

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

    package: vehicle_launch
    vehicle.launch.xml...
    system.launch.xml

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

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

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

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

    package: control_launch
    awapi_awiv_adapter.launch.xml...
    autoware_web_controller.launch.xml

    package: control_launch
    autoware_web_controller.launch.xml...
    clock_publisher.launch.xml

    package: control_launch
    clock_publisher.launch.xml...
    rviz2

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

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

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

    package: vehicle_launch
    vehicle_description.launch.xml...
    system.launch.xml

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

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

    package: perception_launch
    perception.launch.xml...
    planning.launch.xml

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

    package: control_launch
    control.launch.py...
    autoware_web_controller.launch.xml

    package: control_launch
    autoware_web_controller.launch.xml...
    rviz2

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

    package: sensing_launch
    sensing.launch.xml...
    sensing.launch.xml

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

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

    package: simulator_launch
    simulator.launch.xml...
    simulator.launch.xml

    package: simulator_launch
    simulator.launch.xml...
    Viewer does not support full SVG 1.1
    \ No newline at end of file diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index f0163bd35c..aa8d0c58fd 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -18,7 +18,6 @@ - diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 762eeea51f..d57e655bd4 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -19,6 +19,7 @@ + @@ -28,11 +29,11 @@ - + - + @@ -104,4 +105,10 @@ + + + + + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 1ff00231f2..c159e711e4 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -27,10 +27,7 @@ - - - @@ -72,5 +69,8 @@ + + + diff --git a/simulator_launch/README.md b/simulator_launch/README.md index 4864936a28..d52b6c16a6 100644 --- a/simulator_launch/README.md +++ b/simulator_launch/README.md @@ -1,5 +1,9 @@ # simulator_launch +## Structure + +![simulator_launch](./simulator_launch.drawio.svg) + ## Package Dependencies Please see `` in `package.xml`. diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index 507a7fd952..b89b46970b 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -1,8 +1,14 @@ - - - - + + + + + + + + + + @@ -17,4 +23,15 @@
    + + + + + + + + + + + diff --git a/simulator_launch/package.xml b/simulator_launch/package.xml index 9ef9700a31..324c411cd8 100644 --- a/simulator_launch/package.xml +++ b/simulator_launch/package.xml @@ -12,6 +12,7 @@ dummy_perception_publisher fault_injection + simple_planning_simulator ament_lint_auto ament_lint_common diff --git a/simulator_launch/simulator_launch.drawio.svg b/simulator_launch/simulator_launch.drawio.svg new file mode 100644 index 0000000000..d86b068066 --- /dev/null +++ b/simulator_launch/simulator_launch.drawio.svg @@ -0,0 +1,4 @@ + + + +
    simulator.launch.xml

    package: simulator_launch
    simulator.launch.xml...
    fault_injection.launch.xml

    package: fault_injection
    fault_injection.launch.xm...
    simple_planning_simulator.launch.xml

    package: simple_planning_simulator
    simple_planning_simulator.launch.xml...
    True
    True
    $(var vehicle_simulation)
    $(var vehicle_simulation)
    launch name

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

    package: package name
    node name...
    $(var scenario_simulation)
    $(var scenario_simulation)
    False
    False
    other name

    package: package name
    other name...
    True
    True
    $(var scenario_simulation)
    $(var scenario_simulation)
    False
    False
    dummy_perception_publisher.launch.xml

    package: dummy_perception_publisher
    dummy_perception_publisher.launch.xml...
    Viewer does not support full SVG 1.1
    \ No newline at end of file diff --git a/vehicle_launch/README.md b/vehicle_launch/README.md index eba3f836a3..a82a1e3bc5 100644 --- a/vehicle_launch/README.md +++ b/vehicle_launch/README.md @@ -19,11 +19,6 @@ You can include as follows in `*.launch.xml` to use `vehicle.launch.xml`. - - - - - ``` diff --git a/vehicle_launch/launch/vehicle.launch.xml b/vehicle_launch/launch/vehicle.launch.xml index 5b700daa6a..ea73e5ff44 100644 --- a/vehicle_launch/launch/vehicle.launch.xml +++ b/vehicle_launch/launch/vehicle.launch.xml @@ -4,9 +4,9 @@ - + + - @@ -18,11 +18,9 @@ - - - - - - - + + + + + diff --git a/vehicle_launch/launch/vehicle_interface.launch.xml b/vehicle_launch/launch/vehicle_interface.launch.xml deleted file mode 100644 index 0a921aad2f..0000000000 --- a/vehicle_launch/launch/vehicle_interface.launch.xml +++ /dev/null @@ -1,29 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/vehicle_launch/package.xml b/vehicle_launch/package.xml index c463f17c29..a0dd136024 100644 --- a/vehicle_launch/package.xml +++ b/vehicle_launch/package.xml @@ -14,7 +14,6 @@ imu_description livox_description robot_state_publisher - simple_planning_simulator velodyne_description xacro diff --git a/vehicle_launch/vehicle_launch.drawio.svg b/vehicle_launch/vehicle_launch.drawio.svg index d3165a3a54..13acf18829 100644 --- a/vehicle_launch/vehicle_launch.drawio.svg +++ b/vehicle_launch/vehicle_launch.drawio.svg @@ -1,442 +1,4 @@ - - - - - - - -
    -
    -
    - vehicle.launch.xml -
    -
    -
    - - package: vehicle_launch - -
    -
    -
    -
    -
    - - vehicle.launch.xml... - -
    -
    - - - - -
    -
    -
    - vehicle_description.launch.xml -
    -
    -
    - package: vehicle_launch -
    -
    -
    -
    -
    - - vehicle_description.launch.xml... - -
    -
    - - - - - - - - -
    -
    -
    - vehicle_interface.launch.xml -
    -
    -
    - - package: vehicle_launch - -
    -
    -
    -
    -
    - - vehicle_interface.launch.xml... - -
    -
    - - - - -
    -
    -
    - simple_planning_simulator.launch.xml -
    -
    -
    - - package: simple_planning_simulator - -
    -
    -
    -
    -
    - - simple_planning_simulator.launch.xml... - -
    -
    - - - - - -
    -
    -
    - True -
    -
    -
    -
    - - True - -
    -
    - - - - -
    -
    -
    - vehicle_interface.launch.xml -
    -
    -
    - - package: $(var vehicle_model)_description - -
    -
    -
    -
    -
    - - vehicle_interface.launch.xml... - -
    -
    - - - - - -
    -
    -
    - False -
    -
    -
    -
    - - False - -
    -
    - - - - - - -
    -
    -
    - $(var simulation) -
    -
    -
    -
    - - $(var simulation) - -
    -
    - - - - -
    -
    -
    - vehicle.xacro -
    -
    -
    - - package: vehicle_launch - -
    -
    - - -
    -
    -
    -
    -
    - - vehicle.xacro... - -
    -
    - - - - - - -
    -
    -
    - vehicle.xacro -
    -
    - package: $(var vehicle_model)_description -
    -
    -
    -
    - - vehicle.xacro... - -
    -
    - - - - -
    -
    -
    - sensors.xacro -
    -
    -
    - - package: $(var sensor_model)_description - -
    -
    -
    -
    -
    - - sensors.xacro... - -
    -
    - - - - - - - - -
    -
    -
    - launch name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - launch name... - -
    -
    - - - - -
    -
    -
    - ex: -
    -
    -
    -
    - - ex: - -
    -
    - - - - - - -
    -
    -
    - node name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - node name... - -
    -
    - - - - -
    -
    -
    - robot state_publisher -
    -
    -
    - - package: robot_state_publisher - -
    -
    -
    -
    -
    - - robot state_publisher... - -
    -
    - - - - -
    -
    -
    - $(var scenario_simulation) -
    -
    -
    -
    - - $(var scenario_simulation) - -
    -
    - - - - - -
    -
    -
    - False -
    -
    -
    -
    - - False - -
    -
    - - - - -
    -
    -
    - other name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - other name... - -
    -
    - - - - -
    -
    -
    - vehicle_info.launch.py -
    -
    -
    - - package: vehicle_launch - -
    -
    -
    -
    -
    - - vehicle_info.launch.py... - -
    -
    -
    - - - - - Viewer does not support full SVG 1.1 - - - -
    \ No newline at end of file + + + +
    vehicle.launch.xml

    package: vehicle_launch
    vehicle.launch.xml...
    vehicle_description.launch.xml

    package: vehicle_launch
    vehicle_description.launch.xml...
    vehicle_interface.launch.xml

    package: $(var vehicle_model)_description
    vehicle_interface.launch.xml...
    False
    False
    $(var simulation)
    $(var simulation)
    vehicle.xacro

    package: vehicle_launch
      
    vehicle.xacro...
    vehicle.xacro

    package: $(var vehicle_model)_description
    vehicle.xacro...
    sensors.xacro

    package: $(var sensor_model)_description
    sensors.xacro...
    launch name

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

    package: package name
    node name...
    robot state_publisher

    package: robot_state_publisher
    robot state_publisher...
    other name

    package: package name
    other name...
    Viewer does not support full SVG 1.1
    \ No newline at end of file From 322afd10b245c8c38d02ca390e2d9c8e1e199c1a Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Fri, 29 Oct 2021 09:43:25 +0900 Subject: [PATCH 260/851] Add .prettierignore (#479) Signed-off-by: Kenji Miyake --- .pre-commit-config.yaml | 1 - .prettierignore | 2 ++ 2 files changed, 2 insertions(+), 1 deletion(-) create mode 100644 .prettierignore diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 63358e031a..2e8257c37e 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -43,7 +43,6 @@ repos: rev: v2.4.1 hooks: - id: prettier - exclude: "(.rviz|.param.yaml|traffic_light_camera.yaml)" - repo: https://github.com/tier4/pre-commit-hooks-ros rev: v0.3.0 diff --git a/.prettierignore b/.prettierignore new file mode 100644 index 0000000000..a3c34d00a1 --- /dev/null +++ b/.prettierignore @@ -0,0 +1,2 @@ +*.param.yaml +*.rviz From 6b7f86604c5b734ee43d6ceec01988b846f85506 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Fri, 29 Oct 2021 17:40:28 +0900 Subject: [PATCH 261/851] Add sensor_model to system_launch (#480) Signed-off-by: Kenji Miyake --- autoware_launch/launch/autoware.launch.xml | 1 + autoware_launch/launch/logging_simulator.launch.xml | 1 + autoware_launch/launch/planning_simulator.launch.xml | 1 + .../config/diagnostic_aggregator/vehicle.param.yaml | 11 +++++++++++ system_launch/launch/system.launch.xml | 5 +++++ 5 files changed, 19 insertions(+) create mode 100644 system_launch/config/diagnostic_aggregator/vehicle.param.yaml diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index aa8d0c58fd..0fd8eaa296 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -23,6 +23,7 @@ + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index d57e655bd4..8f149321df 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -41,6 +41,7 @@ + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index c159e711e4..8738ca011c 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -33,6 +33,7 @@ + diff --git a/system_launch/config/diagnostic_aggregator/vehicle.param.yaml b/system_launch/config/diagnostic_aggregator/vehicle.param.yaml new file mode 100644 index 0000000000..e96e3b3b05 --- /dev/null +++ b/system_launch/config/diagnostic_aggregator/vehicle.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + vehicle: + type: diagnostic_aggregator/AnalyzerGroup + path: vehicle + analyzers: + vehicle_errors: + type: diagnostic_aggregator/GenericAnalyzer + path: vehicle_errors + contains: [": vehicle_errors"] + timeout: 1.0 diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index b51e286361..af34ae61e5 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -1,6 +1,9 @@ + + + @@ -31,6 +34,8 @@ + + From 3f75be98fa1ec505830e2c35a0cfae484a000ca5 Mon Sep 17 00:00:00 2001 From: "autoware-iv-sync-ci[bot]" <87871706+autoware-iv-sync-ci[bot]@users.noreply.github.com> Date: Mon, 1 Nov 2021 04:39:31 +0900 Subject: [PATCH 262/851] Auto-update pre-commit hooks (#485) Co-authored-by: kenji-miyake --- .pre-commit-config.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 2e8257c37e..993cf203df 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -45,13 +45,13 @@ repos: - id: prettier - repo: https://github.com/tier4/pre-commit-hooks-ros - rev: v0.3.0 + rev: v0.4.0 hooks: - id: prettier-package-xml - id: sort-package-xml - repo: https://github.com/gruntwork-io/pre-commit - rev: v0.1.16 + rev: v0.1.17 hooks: - id: shellcheck From ed2bd637e0b1b697c61abfe33bf82c527b0496f1 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 1 Nov 2021 12:49:44 +0900 Subject: [PATCH 263/851] Fix/revert initial engage state (#484) * Fix args Signed-off-by: Kenji Miyake * Add initial_engage_state to vehicle.launch.xml Signed-off-by: Kenji Miyake * Update vehicle.launch.xml --- simulator_launch/launch/simulator.launch.xml | 3 ++- vehicle_launch/README.md | 2 +- vehicle_launch/launch/vehicle.launch.xml | 6 ++++-- 3 files changed, 7 insertions(+), 4 deletions(-) diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index b89b46970b..0253d8d094 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -7,9 +7,10 @@ - + + diff --git a/vehicle_launch/README.md b/vehicle_launch/README.md index a82a1e3bc5..837c12d023 100644 --- a/vehicle_launch/README.md +++ b/vehicle_launch/README.md @@ -31,7 +31,7 @@ ex.) ```xml - + ``` diff --git a/vehicle_launch/launch/vehicle.launch.xml b/vehicle_launch/launch/vehicle.launch.xml index ea73e5ff44..3ab8513d0b 100644 --- a/vehicle_launch/launch/vehicle.launch.xml +++ b/vehicle_launch/launch/vehicle.launch.xml @@ -3,10 +3,11 @@ + + - + - @@ -21,6 +22,7 @@ + From 5e2d7aa7deafd7e43416fd62633746e864419470 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:10 +0900 Subject: [PATCH 264/851] hide traffic light id by default (#286) Co-authored-by: satoshi-ota --- autoware_launch/rviz/autoware.rviz | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 76ea5a1502..8d8d840dcb 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -384,6 +384,7 @@ Visualization Manager: road_lanelets: false stop_lines: true traffic_light: true + traffic_light_id: false traffic_light_triangle: true walkway_lanelets: true Topic: From f39ac145423f36af9982700000e7b8c87045c2f0 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:10 +0900 Subject: [PATCH 265/851] remove yaw-recalc param in mpc (#190) (#294) Co-authored-by: tkimura4 --- control_launch/config/mpc_follower/mpc_follower.param.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/control_launch/config/mpc_follower/mpc_follower.param.yaml b/control_launch/config/mpc_follower/mpc_follower.param.yaml index 72a9fcd8db..9aa14101a9 100644 --- a/control_launch/config/mpc_follower/mpc_follower.param.yaml +++ b/control_launch/config/mpc_follower/mpc_follower.param.yaml @@ -3,7 +3,6 @@ # -- 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 use_steer_prediction: false # flag for using steer prediction (do not use steer measurement) admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value From 37574af18b8e6048b74caf46dd2f1096f28dbd06 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:10 +0900 Subject: [PATCH 266/851] Master sync for velocity controller (#297) * update velocity_controller_param.yaml for refactoring velocity_controller (#238) * update velocity_controller_param.yaml (#247) Co-authored-by: Takayuki Murooka --- .../velocity_controller.param.yaml | 95 ++++++++++--------- 1 file changed, 49 insertions(+), 46 deletions(-) diff --git a/control_launch/config/velocity_controller/velocity_controller.param.yaml b/control_launch/config/velocity_controller/velocity_controller.param.yaml index 6688822503..f28e5271dc 100644 --- a/control_launch/config/velocity_controller/velocity_controller.param.yaml +++ b/control_launch/config/velocity_controller/velocity_controller.param.yaml @@ -1,36 +1,56 @@ /**: 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 + # slope compensation + enable_slope_compensation: true + + # state transition + drive_state_stop_dist: 0.5 + stopping_state_stop_dist: 0.5 + stopped_state_entry_vel: 0.01 + stopped_state_entry_acc: 0.1 + emergency_state_overshoot_stop_dist: 1.5 + emergency_state_traj_trans_dev: 3.0 + emergency_state_traj_rot_dev: 0.7854 + + # drive state + 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 + lpf_vel_error_gain: 0.9 + current_velocity_threshold_pid_integration: 0.5 + + # smooth stop state + smooth_stop_max_strong_acc: -0.5 + smooth_stop_min_strong_acc: -0.8 + smooth_stop_weak_acc: -0.3 + smooth_stop_weak_stop_acc: -0.8 + smooth_stop_strong_stop_acc: -3.4 + smooth_stop_max_fast_vel: 0.5 + smooth_stop_min_running_vel: 0.01 + smooth_stop_min_running_acc: 0.01 + smooth_stop_weak_stop_time: 0.8 + smooth_stop_weak_stop_dist: -0.3 + smooth_stop_strong_stop_dist: -0.5 - # smooth stop - smooth_stop: - stop_dist: 0.5 - 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 + # stopped state + stopped_vel: 0.0 + stopped_acc: -3.4 + + # emergency state + emergency_vel: 0.0 + emergency_acc: -5.0 + emergency_jerk: -3.0 # acceleration limit max_acc: 3.0 @@ -40,25 +60,8 @@ max_jerk: 2.0 min_jerk: -5.0 - # slope compensation - enable_slope_compensation: true + # pitch use_trajectory_for_pitch_calculation: false + lpf_pitch_gain: 0.95 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.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.0 - min_d_effort: 0.0 - current_velocity_threshold_pid_integration: 0.5 - lpf_velocity_error_gain: 0.9 From 8a5fb2f24b4cc50df0c3b34bd870f3dafb60d615 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:10 +0900 Subject: [PATCH 267/851] add environment_name parameter into localization launch (#175) (#293) * add environment_name parameter into localization launch (#175) * add environment_name parameter into localization launch change launcher parameters of crop_box_filter_mesurement_range and voxel_grid_filter to yaml file Signed-off-by: Azumi Suzuki * change param file directory name Signed-off-by: Azumi Suzuki * Remove redundant comments Signed-off-by: wep21 Co-authored-by: s-azumi <38061530+s-azumi@users.noreply.github.com> --- .../default/crop_box_filter_measurement_range.param.yaml | 9 +++++++++ .../config/{ => default}/ndt_scan_matcher.param.yaml | 0 .../config/default/voxel_grid_filter.param.yaml | 5 +++++ .../launch/pose_estimator/pose_estimator.launch.xml | 4 +++- localization_launch/launch/util/util.launch.xml | 1 + 5 files changed, 18 insertions(+), 1 deletion(-) create mode 100644 localization_launch/config/default/crop_box_filter_measurement_range.param.yaml rename localization_launch/config/{ => default}/ndt_scan_matcher.param.yaml (100%) create mode 100644 localization_launch/config/default/voxel_grid_filter.param.yaml diff --git a/localization_launch/config/default/crop_box_filter_measurement_range.param.yaml b/localization_launch/config/default/crop_box_filter_measurement_range.param.yaml new file mode 100644 index 0000000000..03d969ba51 --- /dev/null +++ b/localization_launch/config/default/crop_box_filter_measurement_range.param.yaml @@ -0,0 +1,9 @@ +/**: + ros__parameters: + 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 diff --git a/localization_launch/config/ndt_scan_matcher.param.yaml b/localization_launch/config/default/ndt_scan_matcher.param.yaml similarity index 100% rename from localization_launch/config/ndt_scan_matcher.param.yaml rename to localization_launch/config/default/ndt_scan_matcher.param.yaml diff --git a/localization_launch/config/default/voxel_grid_filter.param.yaml b/localization_launch/config/default/voxel_grid_filter.param.yaml new file mode 100644 index 0000000000..51a7ee9d89 --- /dev/null +++ b/localization_launch/config/default/voxel_grid_filter.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + voxel_size_x: 3.0 + voxel_size_y: 3.0 + voxel_size_z: 3.0 diff --git a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml index ce949fd34b..6eb082bbe4 100644 --- a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml +++ b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml @@ -1,5 +1,7 @@ + + @@ -10,7 +12,7 @@ - + diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 6d2cc29549..79ae340ed1 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -1,5 +1,6 @@ + From 265fe1701592cc05f98dbbfe17a241f57648675e Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:10 +0900 Subject: [PATCH 268/851] Fix parameter type (#299) 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 f28e5271dc..f754b5a856 100644 --- a/control_launch/config/velocity_controller/velocity_controller.param.yaml +++ b/control_launch/config/velocity_controller/velocity_controller.param.yaml @@ -18,15 +18,15 @@ # drive state 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 lpf_vel_error_gain: 0.9 current_velocity_threshold_pid_integration: 0.5 From de4918efd241d913e4c0de0c28511f9f24e58010 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:10 +0900 Subject: [PATCH 269/851] Feature/porting behavior path planner (#300) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * modify behavior_planning launch for behavior_path_planner with lane_c… (#239) * modify behavior_planning launch for behavior_path_planner with lane_change_only config Signed-off-by: Takamasa Horibe * remove avoidance & side_shift related code Signed-off-by: Takamasa Horibe * Fix launcher and add config files and change obstacle avoid param * Add new line * Fix visualization and remove multiple args * Enable auto approve path change Co-authored-by: rej55 Signed-off-by: wep21 * add param in behavior_path_planner (#255) Signed-off-by: Takamasa Horibe * Fix param (#251) * Fix typo Signed-off-by: wep21 Co-authored-by: Takamasa Horibe Co-authored-by: rej55 --- autoware_launch/rviz/autoware.rviz | 22 +-- .../avoidance/avoidance.param.yaml | 20 +++ .../behavior_path_planner.param.yaml | 11 ++ .../lane_change/lane_change.param.yaml | 20 +++ .../side_shift/side_shift.param.yaml | 9 ++ .../obstacle_avoidance_planner.param.yaml | 4 +- .../behavior_planning.launch.py | 130 +++++++++++------- .../behavior_planning.launch.xml | 41 +++--- 8 files changed, 158 insertions(+), 99 deletions(-) create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 8d8d840dcb..cad026f889 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1039,34 +1039,16 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: 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 - 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 Color Border Vel Max: 3 Enabled: true - Name: LaneChangeCandidate + Name: PathChangeCandidate Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/lane_change_candidate_path + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/output/path_candidate Value: true View Path: Alpha: 0.30000001192092896 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml new file mode 100644 index 0000000000..7b5e6b96b8 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -0,0 +1,20 @@ +# see AvoidanceParameters description in avoidance_module.hpp for description. +/**: + ros__parameters: + avoidance: + threshold_distance_object_is_on_center: 0.0 # [m] + threshold_speed_object_is_stopped: 1.0 # [m/s] + object_check_forward_distance: 150.0 # [m] + object_check_backward_distance: 2.0 # [m] + lateral_collision_margin: 2.0 # [m] + longitudinal_collision_margin: 3.0 # [m] + time_to_start_avoidance: 1.0 # [s] + min_distance_to_start_avoidance: 1.0 # [m] + time_avoiding: 7.0 # [s] + min_distance_avoiding: 50.0 # [m] + + min_distance_avoidance_end_to_object: 5.0 # [m] + time_avoidance_end_to_object: 1.0 # [s] + + nominal_lateral_jerk: 0.3 # [m/s3] + max_lateral_jerk: 2.0 # [m/s3] diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml new file mode 100644 index 0000000000..b25707950e --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + backward_path_length: 5.0 + forward_path_length: 300.0 + backward_length_buffer_for_end_of_lane: 5.0 + minimum_lane_change_length: 12.0 + drivable_area_resolution: 0.1 + drivable_area_width: 100.0 + drivable_area_height: 50.0 + refine_goal_search_radius_range: 7.5 + intersection_search_distance: 30.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml new file mode 100644 index 0000000000..50934a7454 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -0,0 +1,20 @@ +/**: + ros__parameters: + lane_change: + min_stop_distance: 5.0 + stop_time: 2.0 + hysteresis_buffer_distance: 2.0 + lane_change_prepare_duration: 4.0 + lane_changing_duration: 8.0 + lane_change_finish_judge_buffer: 3.0 + minimum_lane_change_velocity: 5.6 + prediction_duration: 8.0 + prediction_time_resolution: 0.5 + static_obstacle_velocity_thresh: 1.5 + maximum_deceleration: 1.0 + enable_abort_lane_change: false + enable_collision_check_at_prepare_phase: false + use_predicted_path_outside_lanelet: false + use_all_predicted_path: false + enable_blocked_by_obstacle: false + lane_change_search_distance: 30.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml new file mode 100644 index 0000000000..dabe370faf --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml @@ -0,0 +1,9 @@ +/**: + ros__parameters: + side_shift: + min_fix_distance: 20.0 + start_avoid_sec: 4.0 + drivable_area_resolution: 0.1 + drivable_area_width: 100.0 + drivable_area_height: 50.0 + inside_outside_judge_margin: 0.3 diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 0615aa1073..52620f1d3c 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -2,8 +2,8 @@ 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] + forward_fixing_distance: 5.0 # forward fixing length from base_link[m] + backward_fixing_distance: 3.0 # backward fixing length from base_link[m] # clearance(distance) when generating trajectory clearance_from_road: 0.2 # clearance from road boundary[m] diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index c88a203caa..8d832fc2af 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -24,54 +24,100 @@ from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer from launch_ros.descriptions import ComposableNode +from launch_ros.substitutions import FindPackageShare import yaml def generate_launch_description(): - # lane change planner - lane_change_planner_param_path = os.path.join( + # behavior path planner + side_shift_param_path = os.path.join( get_package_share_directory('planning_launch'), 'config', 'scenario_planning', 'lane_driving', 'behavior_planning', - 'lane_change_planner', - 'lane_change_planner.param.yaml', + 'behavior_path_planner', + 'side_shift', + 'side_shift.param.yaml', ) - with open(lane_change_planner_param_path, 'r') as f: - lane_change_planner_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(side_shift_param_path, 'r') as f: + side_shift_param = yaml.safe_load(f)['/**']['ros__parameters'] - lane_change_planner_component = ComposableNode( - package='lane_change_planner', - plugin='lane_change_planner::LaneChanger', - name='lane_change_planner', + avoidance_param_path = os.path.join( + get_package_share_directory('planning_launch'), + 'config', + 'scenario_planning', + 'lane_driving', + 'behavior_planning', + 'behavior_path_planner', + 'avoidance', + 'avoidance.param.yaml', + ) + with open(avoidance_param_path, 'r') as f: + avoidance_param = yaml.safe_load(f)['/**']['ros__parameters'] + + lane_change_param_path = os.path.join( + get_package_share_directory('planning_launch'), + 'config', + 'scenario_planning', + 'lane_driving', + 'behavior_planning', + 'behavior_path_planner', + 'lane_change', + 'lane_change.param.yaml', + ) + with open(lane_change_param_path, 'r') as f: + lane_change_param = yaml.safe_load(f)['/**']['ros__parameters'] + + behavior_path_planner_param_path = os.path.join( + get_package_share_directory('planning_launch'), + 'config', + 'scenario_planning', + 'lane_driving', + 'behavior_planning', + 'behavior_path_planner', + 'behavior_path_planner.param.yaml', + ) + with open(behavior_path_planner_param_path, 'r') as f: + behavior_path_planner_param = yaml.safe_load(f)['/**']['ros__parameters'] + + behavior_path_planner_component = ComposableNode( + package='behavior_path_planner', + plugin='behavior_path_planner::BehaviorPathPlannerNode', + name='behavior_path_planner', namespace='', remappings=[ ('~/input/route', LaunchConfiguration('input_route_topic_name')), ('~/input/vector_map', LaunchConfiguration('map_topic_name')), ('~/input/perception', '/perception/object_recognition/objects'), ('~/input/velocity', '/localization/twist'), - ('~/input/lane_change_approval', - '/planning/scenario_planning/lane_driving/lane_change_approval'), - ('~/input/force_lane_change', - '/planning/scenario_planning/lane_driving/force_lane_change'), - ('~/output/lane_change_path', 'path_with_lane_id'), - ('~/output/lane_change_ready', - '/planning/scenario_planning/lane_driving/lane_change_ready'), - ('~/output/lane_change_available', - '/planning/scenario_planning/lane_driving/lane_change_available'), - ('~/output/stop_reasons', '/planning/scenario_planning/status/stop_reasons'), - ('~/debug/lane_change_candidate_path', - '/planning/scenario_planning/lane_driving/lane_change_candidate_path'), + ('~/input/external_approval', + '/planning/scenario_planning/lane_driving/behavior_planning/' + 'behavior_path_planner/path_change_approval'), + ('~/input/force_approval', + '/planning/scenario_planning/lane_driving/behavior_planning/' + 'behavior_path_planner/path_change_force'), + ('~/output/path', 'path_with_lane_id'), + ('~/output/ready', + '/planning/scenario_planning/lane_driving/behavior_planning/' + 'behavior_path_planner/ready_module'), + ('~/output/running', + '/planning/scenario_planning/lane_driving/behavior_planning/' + 'behavior_path_planner/running_modules'), + ('~/output/force_available', + '/planning/scenario_planning/lane_driving/behavior_planning/' + 'behavior_path_planner/force_available'), + ('~/output/turn_signal_cmd', '/planning/turn_signal_decider/turn_signal_cmd'), ], parameters=[ - lane_change_planner_param, + side_shift_param, + avoidance_param, + lane_change_param, + behavior_path_planner_param, { - 'enable_abort_lane_change': False, - 'enable_collision_check_at_prepare_phase': False, - 'use_predicted_path_outside_lanelet': False, - 'use_all_predicted_path': False, - 'enable_blocked_by_obstacle': False, + 'bt_tree_config_path': + [FindPackageShare('behavior_path_planner'), + '/config/behavior_path_planner_tree.xml'] } ], extra_arguments=[ @@ -79,26 +125,6 @@ def generate_launch_description(): ], ) - # turn signal decider - turn_signal_decider_component = ComposableNode( - package='turn_signal_decider', - plugin='turn_signal_decider::TurnSignalDecider', - name='turn_signal_decider', - namespace='', - remappings=[ - ('input/path_with_lane_id', 'path_with_lane_id'), - ('input/vector_map', LaunchConfiguration('map_topic_name')), - ('output/turn_signal_cmd', '/planning/turn_signal_decider/turn_signal_cmd'), - ], - parameters=[ - {'lane_change_search_distance': 30.0}, - {'intersection_search_distance': 30.0}, - ], - extra_arguments=[ - {'use_intra_process_comms': LaunchConfiguration('use_intra_process')} - ], - ) - # behavior velocity planner blind_spot_param_path = os.path.join( get_package_share_directory('behavior_velocity_planner'), @@ -213,8 +239,7 @@ def generate_launch_description(): package='rclcpp_components', executable=LaunchConfiguration('container_executable'), composable_node_descriptions=[ - lane_change_planner_component, - turn_signal_decider_component, + behavior_path_planner_component, behavior_velocity_planner_component, ], output='screen', @@ -252,7 +277,8 @@ def generate_launch_description(): container, ExecuteProcess( cmd=['ros2', 'topic', 'pub', - '/planning/scenario_planning/lane_driving/lane_change_approval', - 'autoware_planning_msgs/msg/LaneChangeCommand', '{command: true}', + '/planning/scenario_planning/lane_driving/behavior_planning/' + 'behavior_path_planner/path_change_approval', + 'autoware_planning_msgs/msg/Approval', '{approval: true}', '-r', '10']), ]) 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 708fe5158d..5fdb56f26b 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,35 +2,26 @@ - + + + - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + From 27dd2f6b82cee00c620d0b8e065db03005f0d101 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:10 +0900 Subject: [PATCH 270/851] Feature/porting motion velocity smoother (#302) * Launch motion_velocity_smoother (#215) * Launch motion_velocity_smoother * Change params * Fix parameter files * Fix Signed-off-by: wep21 * Fix/smoother trajectory ds (#249) * Add parameter * Fix * Fix * change launcher parameter (#265) * Feature/smoother resampling (#269) * change launcher parameter * add new parameter Co-authored-by: Fumiya Watanabe Co-authored-by: purewater0901 <43805014+purewater0901@users.noreply.github.com> --- .../JerkFiltered.param.yaml | 7 +++ .../motion_velocity_smoother/L2.param.yaml | 5 ++ .../motion_velocity_smoother/Linf.param.yaml | 5 ++ .../motion_velocity_smoother.param.yaml | 54 +++++++++++++++++++ .../lane_change_planner.param.yaml | 2 +- .../obstacle_avoidance_planner.param.yaml | 2 +- .../scenario_planning.launch.xml | 11 ++-- 7 files changed, 80 insertions(+), 6 deletions(-) create mode 100644 planning_launch/config/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml create mode 100644 planning_launch/config/scenario_planning/common/motion_velocity_smoother/L2.param.yaml create mode 100644 planning_launch/config/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml create mode 100644 planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml new file mode 100644 index 0000000000..a6906b7117 --- /dev/null +++ b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml @@ -0,0 +1,7 @@ +/**: + ros__parameters: + jerk_weight: 0.1 # weight for "smoothness" cost for jerk + over_v_weight: 10000.0 # weight for "over speed limit" cost + over_a_weight: 500.0 # weight for "over accel limit" cost + over_j_weight: 200.0 # weight for "over jerk limit" cost + jerk_filter_ds: 0.1 # resampling ds for jerk filter diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/L2.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/L2.param.yaml new file mode 100644 index 0000000000..c993978204 --- /dev/null +++ b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/L2.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + pseudo_jerk_weight: 100.0 # weight for "smoothness" cost + over_v_weight: 100000.0 # weight for "over speed limit" cost + over_a_weight: 1000.0 # weight for "over accel limit" cost diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml new file mode 100644 index 0000000000..ec38010621 --- /dev/null +++ b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + pseudo_jerk_weight: 200.0 # weight for "smoothness" cost + over_v_weight: 100000.0 # weight for "over speed limit" cost + over_a_weight: 5000.0 # weight for "over accel limit" cost diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml new file mode 100644 index 0000000000..4231eb1ef8 --- /dev/null +++ b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -0,0 +1,54 @@ +/**: + ros__parameters: + # motion state constraints + max_velocity: 20.0 # max velocity limit [m/s] + max_accel: 1.0 # max acceleration limit [m/ss] + min_decel: -0.5 # min deceleration limit [m/ss] + max_jerk: 1.0 # default maximum jerk limit + min_jerk: -0.5 # default minimum jerk limit + + # external velocity limit parameter + margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m] + + # curve parameters + max_lateral_accel: 0.8 # 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 planning 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. + + # path extraction parameters + 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 trajectory pose [radian] + + # resampling parameters for optimization + max_trajectory_length: 200.0 # max trajectory length for resampling [m] + min_trajectory_length: 150.0 # min trajectory length for resampling [m] + resample_time: 5.0 # resample total time for dense sampling [s] + dense_dt: 0.1 # resample time interval for dense sampling [s] + dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m] + sparse_dt: 0.5 # resample time interval for sparse sampling [s] + sparse_min_interval_distance: 4.0 # minimum points-interval length for sparse sampling [m] + + # resampling parameters for post process + post_max_trajectory_length: 300.0 # max trajectory length for resampling [m] + post_min_trajectory_length: 30.0 # min trajectory length for resampling [m] + post_resample_time: 10.0 # resample total time for dense sampling [s] + post_dense_dt: 0.1 # resample time interval for dense sampling [s] + post_dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m] + post_sparse_dt: 0.1 # resample time interval for sparse sampling [s] + post_sparse_min_interval_distance: 1.0 # minimum points-interval length for sparse sampling [m] + + # system + over_stop_velocity_warn_thr: 1.389 # used to check if the optimization exceeds the input velocity on the stop point diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml index 3e899ca586..0bf42387a6 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml @@ -4,7 +4,7 @@ stop_time: 2.0 hysteresis_buffer_distance: 2.0 backward_path_length: 5.0 - forward_path_length: 200.0 + forward_path_length: 300.0 max_accel: -5.0 lane_change_prepare_duration: 4.0 lane_changing_duration: 8.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 52620f1d3c..8150af7436 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: # trajectory total/fixing length - trajectory_length: 200 # total trajectory length[m] + trajectory_length: 300 # total trajectory length[m] forward_fixing_distance: 5.0 # forward fixing length from base_link[m] backward_fixing_distance: 3.0 # backward fixing length from base_link[m] diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 0d80c87faf..639cc9b6b1 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -14,10 +14,13 @@ - - - - + + + + + + + From 173120bbdfa6d012f29a24846bbf330e347c90e7 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:10 +0900 Subject: [PATCH 271/851] Master sync parking module (#303) * Add namespace Signed-off-by: wep21 * Add freespace planner config file Signed-off-by: wep21 * Add missing import Signed-off-by: wep21 --- .../freespace_planner.param.yaml | 38 ++++++++++++++++ .../scenario_planning/parking.launch.py | 44 ++++++++----------- .../scenario_planning/parking.launch.xml | 1 + 3 files changed, 57 insertions(+), 26 deletions(-) create mode 100644 planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml diff --git a/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml b/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml new file mode 100644 index 0000000000..72648a9dfd --- /dev/null +++ b/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml @@ -0,0 +1,38 @@ +/**: + ros__parameters: + # -- Node Configurations -- + planning_algorithm: "astar" + waypoints_velocity: 5.0 + update_rate: 10.0 + th_arrived_distance_m: 1.0 + th_stopped_time_sec: 1.0 + th_stopped_velocity_mps: 0.01 + th_course_out_distance_m: 1.0 + replan_when_obstacle_found: true + replan_when_course_out: true + + # -- Configurations common to the all planners -- + # base configs + time_limit: 30000.0 + # robot configs # TODO replace by vehicle_info + robot_length: 4.5 + robot_width: 1.75 + robot_base2back: 1.0 + minimum_turning_radius: 9.0 + maximum_turning_radius: 9.0 + turning_radius_size: 1 + # search configs + theta_size: 144 + angle_goal_range: 6.0 + curve_weight: 1.2 + reverse_weight: 2.0 + lateral_goal_range: 0.5 + longitudinal_goal_range: 2.0 + # costmap configs + obstacle_threshold: 100 + + # -- A* search Configurations -- + astar: + only_behind_solutions: false + use_back: true + distance_heuristic_weight: 1.0 diff --git a/planning_launch/launch/scenario_planning/parking.launch.py b/planning_launch/launch/scenario_planning/parking.launch.py index 0cbdd7a270..fe11b734c4 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.py +++ b/planning_launch/launch/scenario_planning/parking.launch.py @@ -12,6 +12,8 @@ # See the License for the specific language governing permissions and # limitations under the License. +from ament_index_python.packages import get_package_share_directory + import launch from launch.actions import DeclareLaunchArgument from launch.actions import GroupAction @@ -23,8 +25,22 @@ from launch_ros.actions import PushRosNamespace from launch_ros.descriptions import ComposableNode +import os +import yaml + def generate_launch_description(): + freespace_planner_param_path = os.path.join( + get_package_share_directory('planning_launch'), + 'config', + 'scenario_planning', + 'parking', + 'freespace_planner', + 'freespace_planner.param.yaml', + ) + with open(freespace_planner_param_path, 'r') as f: + freespace_planner_param = yaml.safe_load(f)['/**']['ros__parameters'] + container = ComposableNodeContainer( name='parking_container', namespace='', @@ -71,7 +87,7 @@ def generate_launch_description(): ), ComposableNode( package='freespace_planner', - plugin='FreespacePlannerNode', + plugin='freespace_planner::FreespacePlannerNode', name='freespace_planner', remappings=[ ('~/input/route', '/planning/mission_planning/route'), @@ -83,31 +99,7 @@ def generate_launch_description(): ('is_completed', '/planning/scenario_planning/parking/is_completed'), ], parameters=[ - { - 'waypoints_velocity': 5.0, - 'update_rate': 10.0, - 'th_arrived_distance_m': 1.0, - 'th_stopped_time_sec': 1.0, - 'th_stopped_velocity_mps': 0.01, - 'th_course_out_distance_m': 1.0, - 'replan_when_obstacle_found': True, - 'replan_when_course_out': True, - 'use_back': True, - 'only_behind_solutions': False, - 'time_limit': 30000.0, - 'robot_length': 4.5, - 'robot_width': 1.75, - 'robot_base2back': 1.0, - 'minimum_turning_radius': 9.0, - 'theta_size': 144, - 'angle_goal_range': 6.0, - 'curve_weight': 1.2, - 'reverse_weight': 2.0, - 'lateral_goal_range': 0.5, - 'longitudinal_goal_range': 2.0, - 'obstacle_threshold': 100, - 'distance_heuristic_weight': 1.0, - }, + freespace_planner_param, ], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') diff --git a/planning_launch/launch/scenario_planning/parking.launch.xml b/planning_launch/launch/scenario_planning/parking.launch.xml index 5ca9fdca55..f8254c8fa5 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.xml +++ b/planning_launch/launch/scenario_planning/parking.launch.xml @@ -18,6 +18,7 @@ + From 90c458174930af30a1d9ab9f271cc8a872b32293 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:10 +0900 Subject: [PATCH 272/851] add smoothing_num parameter (#263) (#301) * add smoothing_num parameter * change param Co-authored-by: tkimura4 --- control_launch/config/mpc_follower/mpc_follower.param.yaml | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/control_launch/config/mpc_follower/mpc_follower.param.yaml b/control_launch/config/mpc_follower/mpc_follower.param.yaml index 9aa14101a9..e11651495e 100644 --- a/control_launch/config/mpc_follower/mpc_follower.param.yaml +++ b/control_launch/config/mpc_follower/mpc_follower.param.yaml @@ -8,9 +8,10 @@ admissible_yaw_error_rad: 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) + 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_ref_steer: 15 # point-to-point index distance used in curvature calculation (for steer command reference): curvature is calculated from three points p(i-num), p(i), p(i+num) + curvature_smoothing_num_traj: 15 # point-to-point index distance used in curvature calculation (for trajectory): 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 From 39e48acd8a58b095dda3cca5bf998a6a3a181b01 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:10 +0900 Subject: [PATCH 273/851] update rviz config & planner params (#305) Co-authored-by: satoshi-ota --- autoware_launch/rviz/autoware.rviz | 6 ++++++ .../obstacle_stop_planner/obstacle_stop_planner.param.yaml | 4 ++-- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index cad026f889..c96e0433b3 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1095,10 +1095,16 @@ Visualization Manager: Namespaces: collision_polygons: false detection_polygons: false + slow_down_polygons: false + slow_down_detection_polygons: false factor_text: true stop_virtual_wall: true stop_obstacle_point: false stop_obstacle_text: false + virtual_wall/slow_down_start: false + factor_text/slow_down_start: false + virtual_wall/slow_down_end: false + factor_text/slow_down_end: false Topic: Depth: 5 Durability Policy: Volatile diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml index 91beb1e1ca..db3b3dcaea 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml @@ -8,8 +8,8 @@ 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] + slow_down_forward_margin: 5.0 # margin distance from slow down point to vehicle front [m] + slow_down_backward_margin: 5.0 # margin distance from slow down point to vehicle rear [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] From 00cd4242409691217a21f9bb65403d9f5a39f90e Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:10 +0900 Subject: [PATCH 274/851] lidar_detection: apollo instance segmentation -> centerpoint (#225) (#307) Co-authored-by: Yusuke Muramatsu --- .../detection/lidar_based_detection.launch.xml | 5 +---- 1 file changed, 1 insertion(+), 4 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 1f5853ba43..bbf7696381 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,6 @@ - - - - + From 5f7d4a0d52c9bfe87f0ecac8df640702fe30ef79 Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Wed, 27 Oct 2021 18:27:10 +0900 Subject: [PATCH 275/851] Feature/porting occlusion spot (#309) * add occulusion_spot marker (#266) * add blindspot marker * to occlusion spot slow down * remove debug info from marker (#287) * remove debug info from marker * remove debug arrow * fix format * update behavior launch * apply pep8 * fix format Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> --- autoware_launch/rviz/autoware.rviz | 18 ++++++++++++++++++ .../behavior_planning.launch.py | 11 +++++++++++ 2 files changed, 29 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index c96e0433b3..56e174f450 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1039,6 +1039,24 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: OcclusionSpot + Namespaces: + arrow: false + occlusion spot slow down: true + collision: false + info_obstacle: false + obstacle: false + sidewalk: false + slow factor_text: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/occlusion_spot + Value: true - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 8d832fc2af..172a11e406 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -182,6 +182,14 @@ def generate_launch_description(): with open(virtual_traffic_light_param_path, 'r') as f: virtual_traffic_light_param = yaml.safe_load(f)['/**']['ros__parameters'] + occlusion_spot_param_path = os.path.join( + get_package_share_directory('behavior_velocity_planner'), + 'config', + 'occlusion_spot.param.yaml', + ) + with open(occlusion_spot_param_path, 'r') as f: + occlusion_spot_param = yaml.safe_load(f)['/**']['ros__parameters'] + behavior_velocity_planner_component = ComposableNode( package='behavior_velocity_planner', plugin='behavior_velocity_planner::BehaviorVelocityPlannerNode', @@ -199,6 +207,7 @@ def generate_launch_description(): '/external/traffic_light_recognition/traffic_light_states'), ('~/input/virtual_traffic_light_states', '/awapi/tmp/virtual_traffic_light_states'), + ('~/input/occupancy_grid', '/sensing/lidar/occupancy_grid'), ('~/output/path', 'path'), ('~/output/stop_reasons', '/planning/scenario_planning/status/stop_reasons'), @@ -215,6 +224,7 @@ def generate_launch_description(): 'launch_blind_spot': True, 'launch_detection_area': True, 'launch_virtual_traffic_light': True, + 'launch_occlusion_spot': True, 'forward_path_length': 1000.0, 'backward_path_length': 5.0, 'max_accel': -2.8, @@ -227,6 +237,7 @@ def generate_launch_description(): stop_line_param, traffic_light_param, virtual_traffic_light_param, + occlusion_spot_param ], extra_arguments=[{ 'use_intra_process_comms': LaunchConfiguration('use_intra_process') From 9c1a369368efa79b54df3e2006af29221b7a8e31 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:00 +0900 Subject: [PATCH 276/851] add stopped_jerk (#276) (#315) * add stopped_jerk * set stopped_jerk -5.0 Co-authored-by: Takayuki Murooka --- .../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 f754b5a856..5e9bb41d06 100644 --- a/control_launch/config/velocity_controller/velocity_controller.param.yaml +++ b/control_launch/config/velocity_controller/velocity_controller.param.yaml @@ -46,6 +46,7 @@ # stopped state stopped_vel: 0.0 stopped_acc: -3.4 + stopped_jerk: -5.0 # emergency state emergency_vel: 0.0 From c40d92ce3af3ac4325a0ac7f595a432940a1cca9 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:00 +0900 Subject: [PATCH 277/851] Feature/porting camera lidar fusion (#316) * Feature/camera lidar fusion (#248) * change camera lidar fusion node * change default mode of object recognition * change spilit range parameter from 10 to 30 (#272) Co-authored-by: Yukihiro Saito --- autoware_launch/launch/autoware.launch.xml | 2 +- .../launch/logging_simulator.launch.xml | 2 +- ...ra_lidar_fusion_based_detection.launch.xml | 58 ++----------------- 3 files changed, 7 insertions(+), 55 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 0fd8eaa296..cd969f1d6f 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -47,7 +47,7 @@ - + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 8f149321df..dbc45ed714 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -73,7 +73,7 @@ - + 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 2ce4d2d216..926351b853 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 @@ -1,5 +1,4 @@ - @@ -77,67 +76,20 @@ - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + - + - From 67d95bafcc0008850bf03ffade7ec864d3820806 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:00 +0900 Subject: [PATCH 278/851] add underscore to marker namespace (#323) Co-authored-by: satoshi-ota --- 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 56e174f450..3e305f3c92 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1157,11 +1157,11 @@ Visualization Manager: bounds_candidate_top_text: false constrain_rect: false constrain_rect_text: false - constrain_rectlocation: false + constrain_rect_location: false current_vehicle_footprint: false extending_constrain_rect: false extending_constrain_rect_text: false - extending_constrain_rectlocation: false + extending_constrain_rect_location: false fixed_mpt_points: false fixed_points_for_extending: false fixed_points_marker: false From 5afdd756390d446581ae8d8e5aa50f3c241c4442 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:00 +0900 Subject: [PATCH 279/851] Feature/hide verbose marker (#322) * tmp : enable slow down * hide verbose markers * Revert "tmp : enable slow down" This reverts commit 5ad32c5903866d9cf946cc47b0b35cefa359d502. * update rviz tool bar Co-authored-by: satoshi-ota --- autoware_launch/rviz/autoware.rviz | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 3e305f3c92..da04ae10b8 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1109,20 +1109,25 @@ Visualization Manager: Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true - Name: ObstaclePointCLoudStop + Name: ObstacleStop Namespaces: collision_polygons: false detection_polygons: false slow_down_polygons: false slow_down_detection_polygons: false - factor_text: true - stop_virtual_wall: true stop_obstacle_point: false stop_obstacle_text: false - virtual_wall/slow_down_start: false - factor_text/slow_down_start: false - virtual_wall/slow_down_end: false - factor_text/slow_down_end: false + slow_down_obstacle_point: false + slow_down_obstacle_text: false + slow_down_start_virtual_wall: false + slow_down_start_factor_text: false + slow_down_end_virtual_wall: false + slow_down_end_factor_text: false + slow_down_end: false + stop_virtual_wall: true + stop_factor_text: true + slow_down_virtual_wall: true + slow_down_factor_text: true Topic: Depth: 5 Durability Policy: Volatile From 32cf3933b8031adba10da613571018599165af6c Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:00 +0900 Subject: [PATCH 280/851] Use multithread for lane driving planning (#327) Signed-off-by: wep21 --- .../launch/scenario_planning/lane_driving.launch.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch.xml b/planning_launch/launch/scenario_planning/lane_driving.launch.xml index ebceb31b8a..26ed39dde9 100644 --- a/planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving.launch.xml @@ -7,6 +7,7 @@ + @@ -14,6 +15,7 @@ + From d34d0291ac54d2ad0a36468321a7abe7b98b469e Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Wed, 27 Oct 2021 18:27:00 +0900 Subject: [PATCH 281/851] Fix import order of parking.launch.py (#347) Signed-off-by: Kenji Miyake --- planning_launch/launch/scenario_planning/parking.launch.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/planning_launch/launch/scenario_planning/parking.launch.py b/planning_launch/launch/scenario_planning/parking.launch.py index fe11b734c4..b9ccd6cfc7 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.py +++ b/planning_launch/launch/scenario_planning/parking.launch.py @@ -12,8 +12,9 @@ # See the License for the specific language governing permissions and # limitations under the License. -from ament_index_python.packages import get_package_share_directory +import os +from ament_index_python.packages import get_package_share_directory import launch from launch.actions import DeclareLaunchArgument from launch.actions import GroupAction @@ -24,8 +25,6 @@ from launch_ros.actions import ComposableNodeContainer from launch_ros.actions import PushRosNamespace from launch_ros.descriptions import ComposableNode - -import os import yaml From 17af214f9f3ccbd36f5151d74a9874a57bae167f Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT Date: Wed, 27 Oct 2021 18:27:00 +0900 Subject: [PATCH 282/851] Rename param from smooth_stop_max_fast_vel to smooth_stop_min_fast_vel (#351) --- .../config/velocity_controller/velocity_controller.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/control_launch/config/velocity_controller/velocity_controller.param.yaml b/control_launch/config/velocity_controller/velocity_controller.param.yaml index 5e9bb41d06..f9a2f02b58 100644 --- a/control_launch/config/velocity_controller/velocity_controller.param.yaml +++ b/control_launch/config/velocity_controller/velocity_controller.param.yaml @@ -36,7 +36,7 @@ smooth_stop_weak_acc: -0.3 smooth_stop_weak_stop_acc: -0.8 smooth_stop_strong_stop_acc: -3.4 - smooth_stop_max_fast_vel: 0.5 + smooth_stop_min_fast_vel: 0.5 smooth_stop_min_running_vel: 0.01 smooth_stop_min_running_acc: 0.01 smooth_stop_weak_stop_time: 0.8 From 5808e3aaba5a6deb1cc8168ab7f71e6b4f688b0a Mon Sep 17 00:00:00 2001 From: Makoto Kurihara Date: Wed, 27 Oct 2021 18:27:00 +0900 Subject: [PATCH 283/851] Add analytical smoother config (#360) Signed-off-by: Makoto Kurihara --- .../Analytical.param.yaml | 25 +++++++++++++++++++ 1 file changed, 25 insertions(+) create mode 100644 planning_launch/config/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml new file mode 100644 index 0000000000..329714e3d3 --- /dev/null +++ b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml @@ -0,0 +1,25 @@ +/**: + ros__parameters: + resample: + ds_resample: 0.1 + num_resample: 1 + delta_yaw_threshold: 0.785 + + latacc: + enable_constant_velocity_while_turning: false + constant_velocity_dist_threshold: 2.0 + + forward: + max_acc: 1.0 + min_acc: -1.0 + max_jerk: 0.3 + min_jerk: -0.3 + kp: 0.3 + + backward: + start_jerk: -0.1 + min_jerk_mild_stop: -0.3 + min_jerk: -1.5 + min_acc_mild_stop: -1.0 + min_acc: -2.5 + span_jerk: -0.01 From 0b873ad985142eeb934b32a74c5bc8570f55aee4 Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Wed, 27 Oct 2021 18:27:00 +0900 Subject: [PATCH 284/851] update acc param (#358) --- .../obstacle_stop_planner/adaptive_cruise_control.param.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml index 8734776b34..dd76f2c4e5 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml @@ -7,7 +7,8 @@ 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] + obstacle_velocity_thresh_to_start_acc: 1.5 # start adaptive cruise control when the velocity of the forward obstacle exceeds this value [m/s] + obstacle_velocity_thresh_to_stop_acc: 1.0 # stop adaptive cruise control when the velocity of the forward obstacle falls below this value [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] From 561e8136ea2d406c192b85ea26e52a0fd9dee1c0 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 27 Oct 2021 18:27:00 +0900 Subject: [PATCH 285/851] add rosparam for vehicle center optimization (#362) --- .../obstacle_avoidance_planner.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 8150af7436..2a38048a66 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -82,6 +82,7 @@ terminal_path_lat_error_weight: 1000.0 # weight for lateral error at path end point terminal_path_yaw_error_weight: 1000.0 # weight for yaw error at path end point zero_ff_steer_angle: 0.5 # threshold that feed-forward angle becomes zero + optimization_center_offset: 1.5 # replanning & trimming trajectory param outside algorithm min_delta_dist_for_replan: 10.0 # minimum delta dist thres for replan[m] From 1795d024b0253394981a5e0ae40951ef28867f87 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 27 Oct 2021 18:27:00 +0900 Subject: [PATCH 286/851] update ros param for .iv (#353) * update ros param for .iv * forward fixing mpt time: 3.0->1.0 --- .../obstacle_avoidance_planner.param.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 2a38048a66..ff885543f8 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -65,7 +65,8 @@ # 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] - forward_fixing_mpt_distance: 10 # number of fixing points around ego vehicle + forward_fixing_mpt_min_distance: 10 # number of fixing points around ego vehicle + forward_fixing_mpt_time: 1.0 # forward fixing time with current velocity [s] # optimization param for mpt is_hard_fixing_terminal_point: false # hard fixing terminal point From e6ae79d5e84b2ece735350f4aa3973983f57e66c Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 27 Oct 2021 18:27:00 +0900 Subject: [PATCH 287/851] Feature/vehicle gate parametrize acc (#320) * [vehicle_cmd_gate] add acc parameters Signed-off-by: TakaHoribe * fix typo Signed-off-by: TakaHoribe * Update control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml Co-authored-by: tkimura4 Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: tkimura4 --- .../config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml b/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml index fbded96a7b..94b682a6b4 100644 --- a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml +++ b/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml @@ -3,7 +3,8 @@ update_rate: 10.0 system_emergency_heartbeat_timeout: 0.5 external_emergency_stop_heartbeat_timeout: 0.0 - + stop_hold_acceleration: -1.5 + emergency_acceleration: -2.4 vel_lim: 25.0 lon_acc_lim: 5.0 lon_jerk_lim: 5.0 From 3276563224f62a7f3e2bceaf2c8f20b906058c39 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 2 Sep 2021 12:03:37 +0900 Subject: [PATCH 288/851] Fix/obstacle avoid revert some improvements (#381) * Revert "update ros param for .iv (#353)" This reverts commit f7f341ae2b76339e7301e5293918b828f53717d0. * Revert "add rosparam for vehicle center optimization (#362)" This reverts commit 78bbf70de51dc01b8892436102c6ea28dda73d5b. --- .../obstacle_avoidance_planner.param.yaml | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index ff885543f8..8150af7436 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -65,8 +65,7 @@ # 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] - forward_fixing_mpt_min_distance: 10 # number of fixing points around ego vehicle - forward_fixing_mpt_time: 1.0 # forward fixing time with current velocity [s] + forward_fixing_mpt_distance: 10 # number of fixing points around ego vehicle # optimization param for mpt is_hard_fixing_terminal_point: false # hard fixing terminal point @@ -83,7 +82,6 @@ terminal_path_lat_error_weight: 1000.0 # weight for lateral error at path end point terminal_path_yaw_error_weight: 1000.0 # weight for yaw error at path end point zero_ff_steer_angle: 0.5 # threshold that feed-forward angle becomes zero - optimization_center_offset: 1.5 # replanning & trimming trajectory param outside algorithm min_delta_dist_for_replan: 10.0 # minimum delta dist thres for replan[m] From ab3330b8013204d6b54ce55ee1841895c9a299df Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 7 Sep 2021 19:51:33 +0900 Subject: [PATCH 289/851] update side shift param (#370) Signed-off-by: Takamasa Horibe --- .../side_shift/side_shift.param.yaml | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml index dabe370faf..79044041b4 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml @@ -1,9 +1,8 @@ /**: ros__parameters: side_shift: - min_fix_distance: 20.0 - start_avoid_sec: 4.0 - drivable_area_resolution: 0.1 - drivable_area_width: 100.0 - drivable_area_height: 50.0 - inside_outside_judge_margin: 0.3 + min_distance_to_start_shifting: 5.0 + time_to_start_shifting: 1.0 + shifting_lateral_jerk: 0.2 + min_shifting_distance: 5.0 + min_shifting_speed: 5.56 From 7fb1a76fe370f597ac8658aafbdb784b7a22f185 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 9 Sep 2021 17:46:33 +0900 Subject: [PATCH 290/851] Add vehicle status launch (#395) --- .../launch/include/external_api_adaptor.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_api_launch/launch/include/external_api_adaptor.launch.py b/autoware_api_launch/launch/include/external_api_adaptor.launch.py index 22e501db81..bdf807b0cf 100644 --- a/autoware_api_launch/launch/include/external_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/external_api_adaptor.launch.py @@ -40,6 +40,7 @@ def generate_launch_description(): _create_api_node('route', 'Route'), _create_api_node('service', 'Service'), _create_api_node('start', 'Start'), + _create_api_node('vehicle_status', 'VehicleStatus'), _create_api_node('velocity', 'Velocity'), _create_api_node('version', 'Version'), ] From 1b0297bb91822916e58bac501089a4bcefa69161 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 15 Sep 2021 09:42:58 +0900 Subject: [PATCH 291/851] add yaml & load lane following params (#377) --- .../lane_following/lane_following.param.yaml | 7 +++++++ .../behavior_planning/behavior_planning.launch.py | 14 ++++++++++++++ .../behavior_planning/behavior_planning.launch.xml | 1 + 3 files changed, 22 insertions(+) create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml new file mode 100644 index 0000000000..f685f8a657 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml @@ -0,0 +1,7 @@ +/**: + ros__parameters: + lane_following: + expand_drivable_area: false + right_bound_offset: 0.5 + left_bound_offset: 0.5 + lane_change_prepare_duration: 2.0 diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 172a11e406..281d0bb462 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -69,6 +69,19 @@ def generate_launch_description(): with open(lane_change_param_path, 'r') as f: lane_change_param = yaml.safe_load(f)['/**']['ros__parameters'] + lane_following_param_path = os.path.join( + get_package_share_directory('planning_launch'), + 'config', + 'scenario_planning', + 'lane_driving', + 'behavior_planning', + 'behavior_path_planner', + 'lane_following', + 'lane_following.param.yaml', + ) + with open(lane_following_param_path, 'r') as f: + lane_following_param = yaml.safe_load(f)['/**']['ros__parameters'] + behavior_path_planner_param_path = os.path.join( get_package_share_directory('planning_launch'), 'config', @@ -113,6 +126,7 @@ def generate_launch_description(): side_shift_param, avoidance_param, lane_change_param, + lane_following_param, behavior_path_planner_param, { 'bt_tree_config_path': 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 5fdb56f26b..d0c04d1320 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 @@ -19,6 +19,7 @@ + From 6dad0a38bae751387d3eedfefee0f51b14b7fa44 Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Fri, 24 Sep 2021 17:52:04 +0900 Subject: [PATCH 292/851] update rviz config ( add shoulder road lanelets ) (#420) * update rviz config * Apply suggestions from code review * Apply suggestions from code review * Apply suggestions from code review --- autoware_launch/rviz/autoware.rviz | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index da04ae10b8..1919971700 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -383,6 +383,10 @@ Visualization Manager: right_lane_bound: true road_lanelets: false stop_lines: true + shoulder_center_lane_line: false + shoulder_left_lane_bound: true + shoulder_right_lane_bound: true + shoulder_road_lanelets: false traffic_light: true traffic_light_id: false traffic_light_triangle: true From 3d8cb050f529224d38929d2dd85215af7f7da47b Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Mon, 27 Sep 2021 17:15:54 +0900 Subject: [PATCH 293/851] Add fail safe state API (#421) --- .../launch/include/external_api_adaptor.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_api_launch/launch/include/external_api_adaptor.launch.py b/autoware_api_launch/launch/include/external_api_adaptor.launch.py index bdf807b0cf..85adcd4e95 100644 --- a/autoware_api_launch/launch/include/external_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/external_api_adaptor.launch.py @@ -33,6 +33,7 @@ def generate_launch_description(): _create_api_node('door', 'Door'), _create_api_node('emergency', 'Emergency'), _create_api_node('engage', 'Engage'), + _create_api_node('fail_safe_state', 'FailSafeState'), _create_api_node('initial_pose', 'InitialPose'), _create_api_node('map', 'Map'), _create_api_node('operator', 'Operator'), From 9b4332879adc25569217d73acd9fe18574c535e9 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Wed, 29 Sep 2021 13:10:02 +0900 Subject: [PATCH 294/851] delete environment name (#428) --- .../default/crop_box_filter_measurement_range.param.yaml | 9 --------- .../config/default/voxel_grid_filter.param.yaml | 5 ----- .../config/{default => }/ndt_scan_matcher.param.yaml | 0 .../launch/pose_estimator/pose_estimator.launch.xml | 3 +-- localization_launch/launch/util/util.launch.xml | 1 - 5 files changed, 1 insertion(+), 17 deletions(-) delete mode 100644 localization_launch/config/default/crop_box_filter_measurement_range.param.yaml delete mode 100644 localization_launch/config/default/voxel_grid_filter.param.yaml rename localization_launch/config/{default => }/ndt_scan_matcher.param.yaml (100%) diff --git a/localization_launch/config/default/crop_box_filter_measurement_range.param.yaml b/localization_launch/config/default/crop_box_filter_measurement_range.param.yaml deleted file mode 100644 index 03d969ba51..0000000000 --- a/localization_launch/config/default/crop_box_filter_measurement_range.param.yaml +++ /dev/null @@ -1,9 +0,0 @@ -/**: - ros__parameters: - 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 diff --git a/localization_launch/config/default/voxel_grid_filter.param.yaml b/localization_launch/config/default/voxel_grid_filter.param.yaml deleted file mode 100644 index 51a7ee9d89..0000000000 --- a/localization_launch/config/default/voxel_grid_filter.param.yaml +++ /dev/null @@ -1,5 +0,0 @@ -/**: - ros__parameters: - voxel_size_x: 3.0 - voxel_size_y: 3.0 - voxel_size_z: 3.0 diff --git a/localization_launch/config/default/ndt_scan_matcher.param.yaml b/localization_launch/config/ndt_scan_matcher.param.yaml similarity index 100% rename from localization_launch/config/default/ndt_scan_matcher.param.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 6eb082bbe4..c3f35464e4 100644 --- a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml +++ b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml @@ -1,6 +1,5 @@ - @@ -12,7 +11,7 @@ - + diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 79ae340ed1..6d2cc29549 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -1,6 +1,5 @@ - From eea8ef2de055cc7dc3a42b70631152daa2e8c16c Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Wed, 29 Sep 2021 21:02:12 +0900 Subject: [PATCH 295/851] add detection by tracker (#418) add detection by tracker --- .../detection/detection.launch.xml | 4 +- .../lidar_based_detection.launch.xml | 52 +++++++++++++++++-- 2 files changed, 51 insertions(+), 5 deletions(-) diff --git a/perception_launch/launch/object_recognition/detection/detection.launch.xml b/perception_launch/launch/object_recognition/detection/detection.launch.xml index 612be58c59..bdcbda3853 100644 --- a/perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -56,9 +56,9 @@ - + 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 bbf7696381..ec100fdb75 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,6 +1,52 @@ - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 63ff661b48265687caf6312c535cd06ec5d35d9e Mon Sep 17 00:00:00 2001 From: kyoichi sugahara <81.s.kyo.19@gmail.com> Date: Sun, 26 Sep 2021 13:56:24 +0900 Subject: [PATCH 296/851] add pull over/out module (#430) add yaml file and modify BT tree file path modify parameter file add parameter add use_dynamic_object flag in pull out param delete unncesarry parameters delete unnecessary param merge change for jpntaxi delete blank line modify BT file name modify launch file --- .../behavior_path_planner.param.yaml | 3 ++ .../pull_out/pull_out.param.yaml | 26 +++++++++++++++++ .../pull_over/pull_over.param.yaml | 25 +++++++++++++++++ .../behavior_planning.launch.py | 28 +++++++++++++++++++ 4 files changed, 82 insertions(+) create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index b25707950e..fcdcf5c78c 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -3,7 +3,10 @@ backward_path_length: 5.0 forward_path_length: 300.0 backward_length_buffer_for_end_of_lane: 5.0 + backward_length_buffer_for_end_of_pull_over: 5.0 + backward_length_buffer_for_end_of_pull_out: 5.0 minimum_lane_change_length: 12.0 + minimum_pull_over_length: 16.0 drivable_area_resolution: 0.1 drivable_area_width: 100.0 drivable_area_height: 50.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml new file mode 100644 index 0000000000..1d3ec31f43 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml @@ -0,0 +1,26 @@ +/**: + ros__parameters: + pull_out: + min_stop_distance: 2.0 + stop_time: 0.0 + hysteresis_buffer_distance: 1.0 + pull_out_prepare_duration: 4.0 + pull_out_duration: 2.0 + pull_out_finish_judge_buffer: 1.0 + minimum_pull_out_velocity: 2.0 + prediction_duration: 30.0 + prediction_time_resolution: 0.5 + static_obstacle_velocity_thresh: 1.5 + maximum_deceleration: 1.0 + enable_collision_check_at_prepare_phase: false + use_predicted_path_outside_lanelet: false + use_all_predicted_path: false + use_dynamic_object: true + enable_blocked_by_obstacle: false + pull_out_search_distance: 30.0 + before_pull_out_straight_distance: 5.0 + after_pull_out_straight_distance: 5.0 + maximum_lateral_jerk: 2.0 + minimum_lateral_jerk: 0.5 + deceleration_interval: 15.0 + diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml new file mode 100644 index 0000000000..08ab028632 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -0,0 +1,25 @@ +/**: + ros__parameters: + pull_over: + min_stop_distance: 5.0 + stop_time: 2.0 + hysteresis_buffer_distance: 2.0 + pull_over_prepare_duration: 4.0 + pull_over_duration: 2.0 + pull_over_finish_judge_buffer: 3.0 + minimum_pull_over_velocity: 3.0 + prediction_duration: 30.0 + prediction_time_resolution: 0.5 + static_obstacle_velocity_thresh: 1.5 + maximum_deceleration: 1.0 + enable_collision_check_at_prepare_phase: false + use_predicted_path_outside_lanelet: false + use_all_predicted_path: false + enable_blocked_by_obstacle: false + pull_over_search_distance: 30.0 + after_pull_over_straight_distance: 5.0 + before_pull_over_straight_distance: 5.0 + margin_from_boundary: 0.5 + maximum_lateral_jerk: 2.0 + minimum_lateral_jerk: 0.5 + deceleration_interval: 15.0 diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 281d0bb462..b001675f93 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -82,6 +82,32 @@ def generate_launch_description(): with open(lane_following_param_path, 'r') as f: lane_following_param = yaml.safe_load(f)['/**']['ros__parameters'] + pull_over_param_path = os.path.join( + get_package_share_directory('planning_launch'), + 'config', + 'scenario_planning', + 'lane_driving', + 'behavior_planning', + 'behavior_path_planner', + 'pull_over', + 'pull_over.param.yaml', + ) + with open(pull_over_param_path, 'r') as f: + pull_over_param = yaml.safe_load(f)['/**']['ros__parameters'] + + pull_out_param_path = os.path.join( + get_package_share_directory('planning_launch'), + 'config', + 'scenario_planning', + 'lane_driving', + 'behavior_planning', + 'behavior_path_planner', + 'pull_out', + 'pull_out.param.yaml', + ) + with open(pull_out_param_path, 'r') as f: + pull_out_param = yaml.safe_load(f)['/**']['ros__parameters'] + behavior_path_planner_param_path = os.path.join( get_package_share_directory('planning_launch'), 'config', @@ -127,6 +153,8 @@ def generate_launch_description(): avoidance_param, lane_change_param, lane_following_param, + pull_over_param, + pull_out_param, behavior_path_planner_param, { 'bt_tree_config_path': From 70527e36b3541f29c20ac6dff0e1f102b27b80ed Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 30 Sep 2021 19:51:02 +0900 Subject: [PATCH 297/851] Update behavior path planner launch files (#433) * update launch parameters for behavior_path_planner Signed-off-by: TakaHoribe * update param at experiment Signed-off-by: Takamasa Horibe * fix typo Signed-off-by: Takamasa Horibe * Fix indent Co-authored-by: TakaHoribe --- .../avoidance/avoidance.param.yaml | 37 ++++++++++++++----- .../behavior_planning.launch.py | 3 +- 2 files changed, 29 insertions(+), 11 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index 7b5e6b96b8..36317a49f9 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -1,20 +1,37 @@ -# see AvoidanceParameters description in avoidance_module.hpp for description. +# see AvoidanceParameters description in avoidance_module_data.hpp for description. /**: ros__parameters: avoidance: + resample_interval_for_planning: 0.3 + resample_interval_for_output: 4.0 + detection_area_right_expand_dist: 0.0 + detection_area_left_expand_dist: 1.0 + threshold_distance_object_is_on_center: 0.0 # [m] threshold_speed_object_is_stopped: 1.0 # [m/s] object_check_forward_distance: 150.0 # [m] object_check_backward_distance: 2.0 # [m] lateral_collision_margin: 2.0 # [m] - longitudinal_collision_margin: 3.0 # [m] - time_to_start_avoidance: 1.0 # [s] - min_distance_to_start_avoidance: 1.0 # [m] - time_avoiding: 7.0 # [s] - min_distance_avoiding: 50.0 # [m] - min_distance_avoidance_end_to_object: 5.0 # [m] - time_avoidance_end_to_object: 1.0 # [s] + prepare_time: 2.0 # [s] + min_prepare_distance: 1.0 # [m] + min_avoidance_distance: 10.0 # [m] + + min_nominal_avoidance_speed: 7.0 # [m/s] + min_sharp_avoidance_speed: 1.0 # [m/s] + + max_right_shift_length: 5.0 + max_left_shift_length: 5.0 + + nominal_lateral_jerk: 0.2 # [m/s3] + max_lateral_jerk: 1.0 # [m/s3] + + object_hold_max_count: 20 + + # for debug + publish_debug_marker: false + print_debug_info: false - nominal_lateral_jerk: 0.3 # [m/s3] - max_lateral_jerk: 2.0 # [m/s3] + # not enabled yet + longitudinal_collision_margin_min_distance: 0.0 # [m] + longitudinal_collision_margin_time: 0.0 diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index b001675f93..7a035f93a0 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -159,7 +159,8 @@ def generate_launch_description(): { 'bt_tree_config_path': [FindPackageShare('behavior_path_planner'), - '/config/behavior_path_planner_tree.xml'] + '/config/behavior_path_planner_tree.xml'], + 'planning_hz': 10.0, } ], extra_arguments=[ From a1938197851afb7c98b863d05ac72418e2b61698 Mon Sep 17 00:00:00 2001 From: Kenji Miyake Date: Mon, 4 Oct 2021 12:39:57 +0900 Subject: [PATCH 298/851] Fix for pre-commit (437) Signed-off-by: Kenji Miyake --- autoware_launch/rviz/autoware.rviz | 2 +- .../behavior_path_planner/pull_out/pull_out.param.yaml | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 1919971700..99a2202f4d 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1128,7 +1128,7 @@ Visualization Manager: slow_down_end_virtual_wall: false slow_down_end_factor_text: false slow_down_end: false - stop_virtual_wall: true + stop_virtual_wall: true stop_factor_text: true slow_down_virtual_wall: true slow_down_factor_text: true diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml index 1d3ec31f43..434545674d 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml @@ -23,4 +23,3 @@ maximum_lateral_jerk: 2.0 minimum_lateral_jerk: 0.5 deceleration_interval: 15.0 - From d314817fab15572a205e6fd26ec59e968a670a78 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 5 Oct 2021 21:33:43 +0900 Subject: [PATCH 299/851] change threshold_distance_object_is_on_center to 1.0 (#441) Signed-off-by: TakaHoribe --- .../behavior_path_planner/avoidance/avoidance.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index 36317a49f9..d52d0ac962 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -7,7 +7,7 @@ detection_area_right_expand_dist: 0.0 detection_area_left_expand_dist: 1.0 - threshold_distance_object_is_on_center: 0.0 # [m] + threshold_distance_object_is_on_center: 1.0 # [m] threshold_speed_object_is_stopped: 1.0 # [m/s] object_check_forward_distance: 150.0 # [m] object_check_backward_distance: 2.0 # [m] From aef5e4baa6c6a9778aa2051fc8e21fd0654bea59 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 12 Oct 2021 13:37:31 +0900 Subject: [PATCH 300/851] Add option to select lidar detection model (#450) Signed-off-by: wep21 --- ...ra_lidar_fusion_based_detection.launch.xml | 14 ++++++++-- .../detection/detection.launch.xml | 3 +++ .../lidar_based_detection.launch.xml | 26 ++++++++++++++++--- 3 files changed, 38 insertions(+), 5 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 926351b853..19c765ef5d 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 @@ -18,6 +18,7 @@ + @@ -43,12 +44,14 @@ + + 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 ec100fdb75..2017a4de1f 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,8 +1,9 @@ + - + @@ -18,7 +19,7 @@ - + @@ -32,10 +33,29 @@ + + + + + + + + + + + + + + + + + + + - + From 53ff71b1636a7b805d2de3a83963ebe4ebe92909 Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Tue, 12 Oct 2021 20:27:47 +0900 Subject: [PATCH 301/851] delete optimizer (#456) --- .../motion_velocity_optimizer.param.yaml | 42 ------------------- planning_launch/package.xml | 2 +- 2 files changed, 1 insertion(+), 43 deletions(-) delete mode 100644 planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.param.yaml diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.param.yaml deleted file mode 100644 index f67d93e3ae..0000000000 --- a/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.param.yaml +++ /dev/null @@ -1,42 +0,0 @@ -/**: - 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/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 - - # 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 planning 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 trajectory 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: 200.0 # weight for "smoothness" cost - over_v_weight: 100000.0 # weight for "overspeed limit" cost - over_a_weight: 5000.0 # weight for "overaccel limit" cost - - algorithm_type: "Linf" # Option : L2, Linf diff --git a/planning_launch/package.xml b/planning_launch/package.xml index 7260c959c5..e26d10aec6 100644 --- a/planning_launch/package.xml +++ b/planning_launch/package.xml @@ -15,7 +15,7 @@ freespace_planner lane_change_planner mission_planner - motion_velocity_optimizer + motion_velocity_smoother obstacle_avoidance_planner obstacle_stop_planner scenario_selector From a95889caa0917bf4e557f58fd0a6ddd85556c61a Mon Sep 17 00:00:00 2001 From: "autoware-iv-sync-ci[bot]" <87871706+autoware-iv-sync-ci[bot]@users.noreply.github.com> Date: Wed, 13 Oct 2021 09:43:24 +0900 Subject: [PATCH 302/851] add params for acceleration prevention (#454) (#457) Signed-off-by: Takamasa Horibe Co-authored-by: Takamasa Horibe --- .../behavior_path_planner/avoidance/avoidance.param.yaml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index d52d0ac962..bfe310b737 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -28,6 +28,10 @@ object_hold_max_count: 20 + # For prevention of large acceleration while avoidance + min_avoidance_speed_for_acc_prevention: 3.0 # [m/s] + max_avoidance_acceleration: 0.5 # [m/ss] + # for debug publish_debug_marker: false print_debug_info: false From d2a791c160c24904b9fcf22f83a382f0974a34cc Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 15 Oct 2021 18:28:11 +0900 Subject: [PATCH 303/851] Feature/use external velocity limit selector (#460) * use external velocity limit selector * add common planning params * update yaml params --- .../scenario_planning/common/common.param.yaml | 15 +++++++++++++++ .../motion_velocity_smoother.param.yaml | 4 ---- .../scenario_planning.launch.xml | 13 +++++++++++-- planning_launch/package.xml | 1 + 4 files changed, 27 insertions(+), 6 deletions(-) create mode 100644 planning_launch/config/scenario_planning/common/common.param.yaml diff --git a/planning_launch/config/scenario_planning/common/common.param.yaml b/planning_launch/config/scenario_planning/common/common.param.yaml new file mode 100644 index 0000000000..a23570a5fc --- /dev/null +++ b/planning_launch/config/scenario_planning/common/common.param.yaml @@ -0,0 +1,15 @@ +/**: + ros__parameters: + # constraints param for normal driving + normal: + min_acc: -0.5 # min deceleration [m/ss] + max_acc: 1.0 # max acceleration [m/ss] + min_jerk: -0.5 # min jerk [m/sss] + max_jerk: 1.0 # max jerk [m/sss] + + # constraints to be observed + limit: + min_acc: -2.5 # min deceleration limit [m/ss] + max_acc: 1.0 # max acceleration limit [m/ss] + min_jerk: -1.5 # min jerk limit [m/sss] + max_jerk: 1.5 # max jerk limit [m/sss] diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index 4231eb1ef8..db13e491b1 100644 --- a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -2,10 +2,6 @@ ros__parameters: # motion state constraints max_velocity: 20.0 # max velocity limit [m/s] - max_accel: 1.0 # max acceleration limit [m/ss] - min_decel: -0.5 # min deceleration limit [m/ss] - max_jerk: 1.0 # default maximum jerk limit - min_jerk: -0.5 # default minimum jerk limit # external velocity limit parameter margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m] diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 639cc9b6b1..1fbb0ba4dd 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 @@ + + @@ -14,15 +16,22 @@ + + + + + + + - + + - diff --git a/planning_launch/package.xml b/planning_launch/package.xml index e26d10aec6..36f5ab20d9 100644 --- a/planning_launch/package.xml +++ b/planning_launch/package.xml @@ -12,6 +12,7 @@ behavior_velocity_planner costmap_generator + external_velocity_limit_selector freespace_planner lane_change_planner mission_planner From f91552ac4d0e15ba66e2208a52abfea7a2050e6c Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 18 Oct 2021 22:56:54 +0900 Subject: [PATCH 304/851] Feature/add slow down params (#448) * add/update slow down params * topic remap * update topic name --- .../obstacle_stop_planner.param.yaml | 20 +++++++++++++++++-- .../motion_planning/motion_planning.launch.py | 4 ++++ 2 files changed, 22 insertions(+), 2 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml index db3b3dcaea..a0fff6bd64 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml @@ -8,8 +8,24 @@ expand_stop_range: 0.0 # margin of vehicle footprint [m] slow_down_planner: - slow_down_forward_margin: 5.0 # margin distance from slow down point to vehicle front [m] - slow_down_backward_margin: 5.0 # margin distance from slow down point to vehicle rear [m] + # slow down planner parameters + forward_margin: 5.0 # margin distance from slow down point to vehicle front [m] + backward_margin: 0.0 # margin distance from slow down point to vehicle rear [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] + + # slow down constraint parameters + consider_constraints: False # set "True", if no decel plan found under jerk/dec constrains, relax target slow down vel + forward_margin_min: 1.0 # min margin for relaxing slow down margin [m/s] + forward_margin_span: -0.1 # fineness param for relaxing slow down margin [m/s] + jerk_min_slow_down: -0.6 # min slow down jerk constraint [m/sss] + jerk_span: -0.01 # fineness param for planning deceleration jerk [m/sss] + slow_down_vel: 1.38 # target slow down velocity [m/s] + + # smoother parameters + jerk_start: -0.1 # init jerk used for deceleration planning [m/sss] + jerk_min: -1.5 # min jerk limit [m/sss] + jerk_min_mild_stop: -0.3 # min jerk limit for mild stop [m/sss] + dec_min: -2.5 # min deceleration limit [m/ss] + dec_min_mild_stop: -1.0 # min deceleration limit for mild stop [m/ss] diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index 5abfdbfc62..4d5d73b254 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -145,6 +145,10 @@ def generate_launch_description(): '/planning/scenario_planning/status/stop_reason'), ('~/output/stop_reasons', '/planning/scenario_planning/status/stop_reasons'), + ('~/output/max_velocity', + '/planning/scenario_planning/max_velocity_candidates'), + ('~/output/velocity_limit_clear_command', + '/planning/scenario_planning/clear_velocity_limit'), ('~/output/trajectory', '/planning/scenario_planning/lane_driving/trajectory'), ('~/input/pointcloud', '/sensing/lidar/no_ground/pointcloud'), From 63805bd634b98f1bfe48e15cf1ad58c0f54355ed Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 19 Oct 2021 15:34:46 +0900 Subject: [PATCH 305/851] Fix/use common param (#465) --- .../obstacle_stop_planner.param.yaml | 8 +------- .../launch/scenario_planning/lane_driving.launch.xml | 2 ++ .../motion_planning/motion_planning.launch.py | 12 ++++++++++++ .../motion_planning/motion_planning.launch.xml | 12 +++++++++--- .../scenario_planning/scenario_planning.launch.xml | 1 + 5 files changed, 25 insertions(+), 10 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml index a0fff6bd64..82a7720334 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml @@ -21,11 +21,5 @@ forward_margin_span: -0.1 # fineness param for relaxing slow down margin [m/s] jerk_min_slow_down: -0.6 # min slow down jerk constraint [m/sss] jerk_span: -0.01 # fineness param for planning deceleration jerk [m/sss] - slow_down_vel: 1.38 # target slow down velocity [m/s] - - # smoother parameters jerk_start: -0.1 # init jerk used for deceleration planning [m/sss] - jerk_min: -1.5 # min jerk limit [m/sss] - jerk_min_mild_stop: -0.3 # min jerk limit for mild stop [m/sss] - dec_min: -2.5 # min deceleration limit [m/ss] - dec_min_mild_stop: -1.0 # min deceleration limit for mild stop [m/ss] + slow_down_vel: 1.38 # target slow down velocity [m/s] diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch.xml b/planning_launch/launch/scenario_planning/lane_driving.launch.xml index 26ed39dde9..e5d4d4c6b8 100644 --- a/planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving.launch.xml @@ -1,4 +1,6 @@ + + diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index 4d5d73b254..d3a3f30493 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -28,6 +28,17 @@ def generate_launch_description(): + # planning common param path + common_param_path = os.path.join( + get_package_share_directory('planning_launch'), + 'config', + 'scenario_planning', + 'common', + 'common.param.yaml', + ) + with open(common_param_path, 'r') as f: + common_param = yaml.safe_load(f)['/**']['ros__parameters'] + # obstacle avoidance planner obstacle_avoidance_planner_param_path = os.path.join( get_package_share_directory('planning_launch'), @@ -157,6 +168,7 @@ def generate_launch_description(): ('~/input/trajectory', 'surround_obstacle_checker/trajectory'), ], parameters=[ + common_param, obstacle_stop_planner_param, obstacle_stop_planner_acc_param, {'enable_slow_down': False} 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 05892f5a25..4e0ee98c72 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,4 +1,7 @@ + + + @@ -33,12 +36,15 @@ + + + + + + - - - diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 1fbb0ba4dd..808cff0110 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -38,6 +38,7 @@ + From 5527a3b1541466aad4586128cb4d1fa715143a12 Mon Sep 17 00:00:00 2001 From: Kenji Miyake Date: Tue, 2 Nov 2021 19:37:45 +0900 Subject: [PATCH 306/851] Change formatter to black (#488) * Update pre-commit settings * Apply Black * Replace ament_lint_common with autoware_lint_common * Update build_depends.repos * Fix build_depends --- .pre-commit-config.yaml | 30 +- .../include/external_api_adaptor.launch.py | 46 +- .../include/internal_api_adaptor.launch.py | 28 +- autoware_api_launch/package.xml | 2 +- autoware_launch/package.xml | 2 +- build_depends.repos | 4 + control_launch/launch/control.launch.py | 396 ++++++++-------- control_launch/package.xml | 2 +- integration_launch/package.xml | 2 +- .../launch/util/util.launch.py | 136 +++--- localization_launch/package.xml | 2 +- map_launch/launch/map.launch.py | 142 +++--- map_launch/package.xml | 2 +- .../traffic_light_node_container.launch.py | 233 +++++---- perception_launch/package.xml | 2 +- .../mission_planning.launch.py | 69 +-- .../behavior_planning.launch.py | 445 +++++++++--------- .../motion_planning/motion_planning.launch.py | 264 +++++------ .../scenario_planning/parking.launch.py | 150 +++--- planning_launch/package.xml | 2 +- sensing_launch/package.xml | 2 +- setup.cfg | 15 + simulator_launch/package.xml | 2 +- system_launch/package.xml | 2 +- vehicle_launch/package.xml | 2 +- 25 files changed, 1002 insertions(+), 980 deletions(-) create mode 100644 setup.cfg diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 993cf203df..59d935c126 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -27,7 +27,6 @@ repos: - id: check-xml - id: check-yaml - id: detect-private-key - - id: double-quote-string-fixer - id: end-of-file-fixer - id: mixed-line-ending - id: trailing-whitespace @@ -55,4 +54,31 @@ repos: hooks: - id: shellcheck -exclude: "(.svg)" + - repo: https://github.com/pycqa/isort + rev: 5.9.3 + hooks: + - id: isort + + - repo: https://github.com/psf/black + rev: 21.9b0 + hooks: + - id: black + args: ["--line-length=100"] + + - repo: https://github.com/PyCQA/flake8 + rev: 4.0.1 + hooks: + - id: flake8 + additional_dependencies: + [ + "flake8-blind-except", + "flake8-builtins", + "flake8-class-newline", + "flake8-comprehensions", + "flake8-deprecated", + "flake8-docstrings", + "flake8-import-order", + "flake8-quotes", + ] + +exclude: ".svg" diff --git a/autoware_api_launch/launch/include/external_api_adaptor.launch.py b/autoware_api_launch/launch/include/external_api_adaptor.launch.py index 85adcd4e95..f81e88a77f 100644 --- a/autoware_api_launch/launch/include/external_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/external_api_adaptor.launch.py @@ -19,38 +19,38 @@ def _create_api_node(node_name, class_name, **kwargs): return ComposableNode( - namespace='external', + namespace="external", name=node_name, - package='autoware_iv_external_api_adaptor', - plugin='external_api::' + class_name, + package="autoware_iv_external_api_adaptor", + plugin="external_api::" + class_name, **kwargs ) def generate_launch_description(): components = [ - _create_api_node('diagnostics', 'Diagnostics'), - _create_api_node('door', 'Door'), - _create_api_node('emergency', 'Emergency'), - _create_api_node('engage', 'Engage'), - _create_api_node('fail_safe_state', 'FailSafeState'), - _create_api_node('initial_pose', 'InitialPose'), - _create_api_node('map', 'Map'), - _create_api_node('operator', 'Operator'), - _create_api_node('metadata_packages', 'MetadataPackages'), - _create_api_node('route', 'Route'), - _create_api_node('service', 'Service'), - _create_api_node('start', 'Start'), - _create_api_node('vehicle_status', 'VehicleStatus'), - _create_api_node('velocity', 'Velocity'), - _create_api_node('version', 'Version'), + _create_api_node("diagnostics", "Diagnostics"), + _create_api_node("door", "Door"), + _create_api_node("emergency", "Emergency"), + _create_api_node("engage", "Engage"), + _create_api_node("fail_safe_state", "FailSafeState"), + _create_api_node("initial_pose", "InitialPose"), + _create_api_node("map", "Map"), + _create_api_node("operator", "Operator"), + _create_api_node("metadata_packages", "MetadataPackages"), + _create_api_node("route", "Route"), + _create_api_node("service", "Service"), + _create_api_node("start", "Start"), + _create_api_node("vehicle_status", "VehicleStatus"), + _create_api_node("velocity", "Velocity"), + _create_api_node("version", "Version"), ] container = ComposableNodeContainer( - namespace='external', - name='autoware_iv_adaptor', - package='rclcpp_components', - executable='component_container_mt', + namespace="external", + name="autoware_iv_adaptor", + package="rclcpp_components", + executable="component_container_mt", composable_node_descriptions=components, - output='screen', + output="screen", ) return launch.LaunchDescription([container]) diff --git a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py index f4e779b584..4a64f42a85 100644 --- a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py @@ -20,31 +20,31 @@ def _create_api_node(node_name, class_name, **kwargs): return ComposableNode( - namespace='internal', + namespace="internal", name=node_name, - package='autoware_iv_internal_api_adaptor', - plugin='internal_api::' + class_name, + package="autoware_iv_internal_api_adaptor", + plugin="internal_api::" + class_name, **kwargs ) def generate_launch_description(): param_initial_pose = { - 'init_simulator_pose': LaunchConfiguration('init_simulator_pose'), - 'init_localization_pose': LaunchConfiguration('init_localization_pose'), + "init_simulator_pose": LaunchConfiguration("init_simulator_pose"), + "init_localization_pose": LaunchConfiguration("init_localization_pose"), } components = [ - _create_api_node('initial_pose', 'InitialPose', parameters=[param_initial_pose]), - _create_api_node('operator', 'Operator'), - _create_api_node('route', 'Route'), - _create_api_node('velocity', 'Velocity'), + _create_api_node("initial_pose", "InitialPose", parameters=[param_initial_pose]), + _create_api_node("operator", "Operator"), + _create_api_node("route", "Route"), + _create_api_node("velocity", "Velocity"), ] container = ComposableNodeContainer( - namespace='internal', - name='autoware_iv_adaptor', - package='rclcpp_components', - executable='component_container_mt', + namespace="internal", + name="autoware_iv_adaptor", + package="rclcpp_components", + executable="component_container_mt", composable_node_descriptions=components, - output='screen', + output="screen", ) return launch.LaunchDescription([container]) diff --git a/autoware_api_launch/package.xml b/autoware_api_launch/package.xml index b9b064d9b4..adc0e0e3a9 100644 --- a/autoware_api_launch/package.xml +++ b/autoware_api_launch/package.xml @@ -17,7 +17,7 @@ topic_tools ament_lint_auto - ament_lint_common + autoware_lint_common ament_cmake diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 5ca5f78f72..3816787753 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -26,7 +26,7 @@ vehicle_launch ament_lint_auto - ament_lint_common + autoware_lint_common ament_cmake diff --git a/build_depends.repos b/build_depends.repos index 56f46b6f79..5e650722cd 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -1 +1,5 @@ repositories: + tier4_ament_lint: + type: git + url: https://github.com/tier4/tier4_ament_lint.git + version: main diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 292e13bf53..4dd0408409 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -32,223 +32,202 @@ def launch_setup(context, *args, **kwargs): - mpc_follower_param_path = \ - LaunchConfiguration('mpc_follower_param_path').perform(context) - with open(mpc_follower_param_path, 'r') as f: - mpc_follower_param = yaml.safe_load(f)['/**']['ros__parameters'] - pure_pursuit_param_path = \ - LaunchConfiguration('pure_pursuit_param_path').perform(context) - with open(pure_pursuit_param_path, 'r') as f: - pure_pursuit_param = yaml.safe_load(f)['/**']['ros__parameters'] - velocity_controller_param_path = \ - LaunchConfiguration('velocity_controller_param_path').perform(context) - with open(velocity_controller_param_path, 'r') as f: - velocity_controller_param = yaml.safe_load(f)['/**']['ros__parameters'] - vehicle_cmd_gate_param_path = \ - LaunchConfiguration('vehicle_cmd_gate_param_path').perform(context) - with open(vehicle_cmd_gate_param_path, 'r') as f: - vehicle_cmd_gate_param = yaml.safe_load(f)['/**']['ros__parameters'] - lane_departure_checker_param_path = \ - LaunchConfiguration('lane_departure_checker_param_path').perform(context) - with open(lane_departure_checker_param_path, 'r') as f: - lane_departure_checker_param = yaml.safe_load(f)['/**']['ros__parameters'] + mpc_follower_param_path = LaunchConfiguration("mpc_follower_param_path").perform(context) + with open(mpc_follower_param_path, "r") as f: + mpc_follower_param = yaml.safe_load(f)["/**"]["ros__parameters"] + pure_pursuit_param_path = LaunchConfiguration("pure_pursuit_param_path").perform(context) + with open(pure_pursuit_param_path, "r") as f: + pure_pursuit_param = yaml.safe_load(f)["/**"]["ros__parameters"] + velocity_controller_param_path = LaunchConfiguration("velocity_controller_param_path").perform( + context + ) + with open(velocity_controller_param_path, "r") as f: + velocity_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] + vehicle_cmd_gate_param_path = LaunchConfiguration("vehicle_cmd_gate_param_path").perform( + context + ) + with open(vehicle_cmd_gate_param_path, "r") as f: + vehicle_cmd_gate_param = yaml.safe_load(f)["/**"]["ros__parameters"] + lane_departure_checker_param_path = LaunchConfiguration( + "lane_departure_checker_param_path" + ).perform(context) + with open(lane_departure_checker_param_path, "r") as f: + lane_departure_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] # mpc follower mpc_follower_component = ComposableNode( - package='mpc_follower', - plugin='MPCFollower', - name='mpc_follower', - namespace='trajectory_follower', + package="mpc_follower", + plugin="MPCFollower", + name="mpc_follower", + namespace="trajectory_follower", remappings=[ - ('~/input/reference_trajectory', '/planning/scenario_planning/trajectory'), - ('~/input/current_velocity', '/localization/twist'), - ('~/input/current_steering', '/vehicle/status/steering'), - ('~/output/control_raw', 'lateral/control_cmd'), - ('~/output/predicted_trajectory', 'predicted_trajectory'), + ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), + ("~/input/current_velocity", "/localization/twist"), + ("~/input/current_steering", "/vehicle/status/steering"), + ("~/output/control_raw", "lateral/control_cmd"), + ("~/output/predicted_trajectory", "predicted_trajectory"), ], parameters=[ mpc_follower_param, ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) # pure pursuit pure_pursuit_component = ComposableNode( - package='pure_pursuit', - plugin='PurePursuitNode', - name='pure_pursuit', - namespace='trajectory_follower', + package="pure_pursuit", + plugin="PurePursuitNode", + name="pure_pursuit", + namespace="trajectory_follower", remappings=[ - ('input/reference_trajectory', '/planning/scenario_planning/trajectory'), - ('input/current_velocity', '/localization/twist'), - ('output/control_raw', 'lateral/control_cmd'), + ("input/reference_trajectory", "/planning/scenario_planning/trajectory"), + ("input/current_velocity", "/localization/twist"), + ("output/control_raw", "lateral/control_cmd"), ], parameters=[ pure_pursuit_param, ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) # velocity controller velocity_controller_component = ComposableNode( - package='velocity_controller', - plugin='VelocityController', - name='velocity_controller', - namespace='trajectory_follower', + package="velocity_controller", + plugin="VelocityController", + name="velocity_controller", + namespace="trajectory_follower", remappings=[ - ('~/current_velocity', '/localization/twist'), - ('~/control_cmd', 'longitudinal/control_cmd'), - ('~/current_trajectory', '/planning/scenario_planning/trajectory'), + ("~/current_velocity", "/localization/twist"), + ("~/control_cmd", "longitudinal/control_cmd"), + ("~/current_trajectory", "/planning/scenario_planning/trajectory"), ], parameters=[ velocity_controller_param, { - 'control_rate': LaunchConfiguration('control_rate'), - 'show_debug_info': LaunchConfiguration('show_debug_info'), - 'enable_smooth_stop': LaunchConfiguration('enable_smooth_stop'), - 'enable_pub_debug': LaunchConfiguration('enable_pub_debug'), - } + "control_rate": LaunchConfiguration("control_rate"), + "show_debug_info": LaunchConfiguration("show_debug_info"), + "enable_smooth_stop": LaunchConfiguration("enable_smooth_stop"), + "enable_pub_debug": LaunchConfiguration("enable_pub_debug"), + }, ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) # latlon muxer latlon_muxer_component = ComposableNode( - package='latlon_muxer', - plugin='LatLonMuxer', - name='latlon_muxer', - namespace='trajectory_follower', + package="latlon_muxer", + plugin="LatLonMuxer", + name="latlon_muxer", + namespace="trajectory_follower", remappings=[ - ('input/lateral/control_cmd', 'lateral/control_cmd'), - ('input/longitudinal/control_cmd', 'longitudinal/control_cmd'), - ('output/control_cmd', 'control_cmd'), + ("input/lateral/control_cmd", "lateral/control_cmd"), + ("input/longitudinal/control_cmd", "longitudinal/control_cmd"), + ("output/control_cmd", "control_cmd"), ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) # lane departure checker lane_departure_component = ComposableNode( - package='lane_departure_checker', - plugin='lane_departure_checker::LaneDepartureCheckerNode', - name='lane_departure_checker_node', - namespace='trajectory_follower', + package="lane_departure_checker", + plugin="lane_departure_checker::LaneDepartureCheckerNode", + name="lane_departure_checker_node", + namespace="trajectory_follower", remappings=[ - ('~/input/twist', '/localization/twist'), - ('~/input/lanelet_map_bin', '/map/vector_map'), - ('~/input/route', '/planning/mission_planning/route'), - ('~/input/reference_trajectory', '/planning/scenario_planning/trajectory'), - ('~/input/predicted_trajectory', '/control/trajectory_follower/predicted_trajectory'), - ('~/input/covariance', '/localization/pose_with_covariance') - ], - parameters=[ - lane_departure_checker_param + ("~/input/twist", "/localization/twist"), + ("~/input/lanelet_map_bin", "/map/vector_map"), + ("~/input/route", "/planning/mission_planning/route"), + ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), + ("~/input/predicted_trajectory", "/control/trajectory_follower/predicted_trajectory"), + ("~/input/covariance", "/localization/pose_with_covariance"), ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + parameters=[lane_departure_checker_param], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) # shift decider shift_decider_component = ComposableNode( - package='shift_decider', - plugin='ShiftDecider', - name='shift_decider', + package="shift_decider", + plugin="ShiftDecider", + name="shift_decider", remappings=[ - ('input/control_cmd', '/control/trajectory_follower/control_cmd'), - ('output/shift_cmd', '/control/shift_decider/shift_cmd'), + ("input/control_cmd", "/control/trajectory_follower/control_cmd"), + ("output/shift_cmd", "/control/shift_decider/shift_cmd"), ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) # vehicle cmd gate vehicle_cmd_gate_component = ComposableNode( - package='vehicle_cmd_gate', - plugin='VehicleCmdGate', - name='vehicle_cmd_gate', + package="vehicle_cmd_gate", + plugin="VehicleCmdGate", + name="vehicle_cmd_gate", remappings=[ - ('input/emergency_state', '/system/emergency/emergency_state'), - ('input/steering', '/vehicle/status/steering'), - - ('input/auto/control_cmd', 'trajectory_follower/control_cmd'), - ('input/auto/turn_signal_cmd', '/planning/turn_signal_decider/turn_signal_cmd'), - ('input/auto/shift_cmd', '/control/shift_decider/shift_cmd'), - - ('input/external/control_cmd', '/external/selected/control_cmd'), - ('input/external/turn_signal_cmd', '/external/selected/turn_signal_cmd'), - ('input/external/shift_cmd', '/external/selected/shift_cmd'), - ('input/external_emergency_stop_heartbeat', '/external/selected/heartbeat'), - ('input/gate_mode', '/control/gate_mode_cmd'), - - ('input/emergency/control_cmd', '/system/emergency/control_cmd'), - ('input/emergency/turn_signal_cmd', '/system/emergency/turn_signal_cmd'), - ('input/emergency/shift_cmd', '/system/emergency/shift_cmd'), - - ('output/vehicle_cmd', 'vehicle_cmd'), - ('output/control_cmd', '/control/control_cmd'), - ('output/shift_cmd', '/control/shift_cmd'), - ('output/turn_signal_cmd', '/control/turn_signal_cmd'), - ('output/gate_mode', '/control/current_gate_mode'), - ('output/engage', '/api/autoware/get/engage'), - ('output/external_emergency', '/api/autoware/get/emergency'), - - ('~/service/engage', '/api/autoware/set/engage'), - ('~/service/external_emergency', '/api/autoware/set/emergency'), - + ("input/emergency_state", "/system/emergency/emergency_state"), + ("input/steering", "/vehicle/status/steering"), + ("input/auto/control_cmd", "trajectory_follower/control_cmd"), + ("input/auto/turn_signal_cmd", "/planning/turn_signal_decider/turn_signal_cmd"), + ("input/auto/shift_cmd", "/control/shift_decider/shift_cmd"), + ("input/external/control_cmd", "/external/selected/control_cmd"), + ("input/external/turn_signal_cmd", "/external/selected/turn_signal_cmd"), + ("input/external/shift_cmd", "/external/selected/shift_cmd"), + ("input/external_emergency_stop_heartbeat", "/external/selected/heartbeat"), + ("input/gate_mode", "/control/gate_mode_cmd"), + ("input/emergency/control_cmd", "/system/emergency/control_cmd"), + ("input/emergency/turn_signal_cmd", "/system/emergency/turn_signal_cmd"), + ("input/emergency/shift_cmd", "/system/emergency/shift_cmd"), + ("output/vehicle_cmd", "vehicle_cmd"), + ("output/control_cmd", "/control/control_cmd"), + ("output/shift_cmd", "/control/shift_cmd"), + ("output/turn_signal_cmd", "/control/turn_signal_cmd"), + ("output/gate_mode", "/control/current_gate_mode"), + ("output/engage", "/api/autoware/get/engage"), + ("output/external_emergency", "/api/autoware/get/emergency"), + ("~/service/engage", "/api/autoware/set/engage"), + ("~/service/external_emergency", "/api/autoware/set/emergency"), # TODO(Takagi, Isamu): deprecated - ('input/engage', '/autoware/engage'), - ('~/service/external_emergency_stop', '~/external_emergency_stop'), - ('~/service/clear_external_emergency_stop', '~/clear_external_emergency_stop'), + ("input/engage", "/autoware/engage"), + ("~/service/external_emergency_stop", "~/external_emergency_stop"), + ("~/service/clear_external_emergency_stop", "~/clear_external_emergency_stop"), ], parameters=[ vehicle_cmd_gate_param, { - 'use_emergency_handling': LaunchConfiguration('use_emergency_handling'), - 'use_external_emergency_stop': LaunchConfiguration('use_external_emergency_stop'), - 'use_start_request': LaunchConfiguration('use_start_request'), - } + "use_emergency_handling": LaunchConfiguration("use_emergency_handling"), + "use_external_emergency_stop": LaunchConfiguration("use_external_emergency_stop"), + "use_start_request": LaunchConfiguration("use_start_request"), + }, ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) # external cmd selector external_cmd_selector_loader = IncludeLaunchDescription( - PythonLaunchDescriptionSource([ - FindPackageShare('external_cmd_selector'), '/launch/external_cmd_selector.launch.py' - ]), + PythonLaunchDescriptionSource( + [FindPackageShare("external_cmd_selector"), "/launch/external_cmd_selector.launch.py"] + ), launch_arguments=[ - ('use_intra_process', LaunchConfiguration('use_intra_process')), - ('target_container', '/control/control_container'), - ('initial_selector_mode', 'remote'), + ("use_intra_process", LaunchConfiguration("use_intra_process")), + ("target_container", "/control/control_container"), + ("initial_selector_mode", "remote"), ], ) # external cmd converter external_cmd_converter_loader = IncludeLaunchDescription( - PythonLaunchDescriptionSource([ - FindPackageShare('external_cmd_converter'), '/launch/external_cmd_converter.launch.py' - ]), + PythonLaunchDescriptionSource( + [FindPackageShare("external_cmd_converter"), "/launch/external_cmd_converter.launch.py"] + ), launch_arguments=[ - ('use_intra_process', LaunchConfiguration('use_intra_process')), - ('target_container', '/control/control_container'), + ("use_intra_process", LaunchConfiguration("use_intra_process")), + ("target_container", "/control/control_container"), ], ) # set container to run all required components in the same process container = ComposableNodeContainer( - name='control_container', - namespace='', - package='rclcpp_components', - executable=LaunchConfiguration('container_executable'), + name="control_container", + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ velocity_controller_component, latlon_muxer_component, @@ -261,27 +240,25 @@ def launch_setup(context, *args, **kwargs): mpc_follower_loader = LoadComposableNodes( composable_node_descriptions=[mpc_follower_component], target_container=container, - condition=LaunchConfigurationEquals( - 'lateral_controller_mode', 'mpc_follower' - ), + condition=LaunchConfigurationEquals("lateral_controller_mode", "mpc_follower"), ) pure_pursuit_loader = LoadComposableNodes( composable_node_descriptions=[pure_pursuit_component], target_container=container, - condition=LaunchConfigurationEquals( - 'lateral_controller_mode', 'pure_pursuit' - ), + condition=LaunchConfigurationEquals("lateral_controller_mode", "pure_pursuit"), ) - group = GroupAction([ - PushRosNamespace('control'), - container, - external_cmd_selector_loader, - external_cmd_converter_loader, - mpc_follower_loader, - pure_pursuit_loader - ]) + group = GroupAction( + [ + PushRosNamespace("control"), + container, + external_cmd_selector_loader, + external_cmd_converter_loader, + mpc_follower_loader, + pure_pursuit_loader, + ] + ) return [group] @@ -290,85 +267,80 @@ def generate_launch_description(): launch_arguments = [] def add_launch_arg(name: str, default_value=None, description=None): - launch_arguments.append(DeclareLaunchArgument( - name, default_value=default_value, description=description)) - add_launch_arg('lateral_controller_mode', 'mpc_follower', - 'lateral controller mode: `mpc_follower` or `pure_pursuit`') + launch_arguments.append( + DeclareLaunchArgument(name, default_value=default_value, description=description) + ) + add_launch_arg( - 'mpc_follower_param_path', - [ - FindPackageShare('control_launch'), - '/config/mpc_follower/mpc_follower.param.yaml' - ], - 'path to the parameter file of mpc_follower' + "lateral_controller_mode", + "mpc_follower", + "lateral controller mode: `mpc_follower` or `pure_pursuit`", ) add_launch_arg( - 'pure_pursuit_param_path', - [ - FindPackageShare('control_launch'), - '/config/pure_pursuit/pure_pursuit.param.yaml' - ], - 'path to the parameter file of pure_pursuit' + "mpc_follower_param_path", + [FindPackageShare("control_launch"), "/config/mpc_follower/mpc_follower.param.yaml"], + "path to the parameter file of mpc_follower", ) add_launch_arg( - 'velocity_controller_param_path', + "pure_pursuit_param_path", + [FindPackageShare("control_launch"), "/config/pure_pursuit/pure_pursuit.param.yaml"], + "path to the parameter file of pure_pursuit", + ) + add_launch_arg( + "velocity_controller_param_path", [ - FindPackageShare('control_launch'), - '/config/velocity_controller/velocity_controller.param.yaml' + FindPackageShare("control_launch"), + "/config/velocity_controller/velocity_controller.param.yaml", ], - 'path to the parameter file of velocity controller' + "path to the parameter file of velocity controller", ) add_launch_arg( - 'vehicle_cmd_gate_param_path', + "vehicle_cmd_gate_param_path", [ - FindPackageShare('control_launch'), - '/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml' + FindPackageShare("control_launch"), + "/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml", ], - 'path to the parameter file of vehicle_cmd_gate' + "path to the parameter file of vehicle_cmd_gate", ) add_launch_arg( - 'lane_departure_checker_param_path', - [ - FindPackageShare('lane_departure_checker'), - '/config/lane_departure_checker.param.yaml' - ] + "lane_departure_checker_param_path", + [FindPackageShare("lane_departure_checker"), "/config/lane_departure_checker.param.yaml"], ) # velocity controller - add_launch_arg('control_rate', '30.0', 'control rate') - add_launch_arg('show_debug_info', 'false', 'show debug information') - add_launch_arg('enable_smooth_stop', 'true', - 'enable smooth stop (in velocity controller state)') - add_launch_arg('enable_pub_debug', 'true', 'enable to publish debug information') + add_launch_arg("control_rate", "30.0", "control rate") + add_launch_arg("show_debug_info", "false", "show debug information") + add_launch_arg( + "enable_smooth_stop", "true", "enable smooth stop (in velocity controller state)" + ) + add_launch_arg("enable_pub_debug", "true", "enable to publish debug information") # vehicle cmd gate - add_launch_arg('use_emergency_handling', 'false', 'use emergency handling') - add_launch_arg('use_external_emergency_stop', 'true', 'use external emergency stop') - add_launch_arg('use_start_request', 'false', 'use start request service') + add_launch_arg("use_emergency_handling", "false", "use emergency handling") + add_launch_arg("use_external_emergency_stop", "true", "use external emergency stop") + add_launch_arg("use_start_request", "false", "use start request service") # external cmd selector - add_launch_arg('initial_selector_mode', 'remote', 'local or remote') + add_launch_arg("initial_selector_mode", "remote", "local or remote") # component - add_launch_arg('use_intra_process', 'false', 'use ROS2 component container communication') - add_launch_arg('use_multithread', 'false', 'use multithread') + add_launch_arg("use_intra_process", "false", "use ROS2 component container communication") + add_launch_arg("use_multithread", "false", "use multithread") set_container_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container', - condition=UnlessCondition(LaunchConfiguration('use_multithread')) + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), ) set_container_mt_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container_mt', - condition=IfCondition(LaunchConfiguration('use_multithread')) + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), ) return launch.LaunchDescription( - launch_arguments + - [ + launch_arguments + + [ set_container_executable, set_container_mt_executable, - ] + - [ - OpaqueFunction(function=launch_setup) ] + + [OpaqueFunction(function=launch_setup)] ) diff --git a/control_launch/package.xml b/control_launch/package.xml index 6c44b73f85..a6ad01d375 100644 --- a/control_launch/package.xml +++ b/control_launch/package.xml @@ -21,7 +21,7 @@ velocity_controller ament_lint_auto - ament_lint_common + autoware_lint_common ament_cmake diff --git a/integration_launch/package.xml b/integration_launch/package.xml index 9bafa3c34a..118963ab77 100644 --- a/integration_launch/package.xml +++ b/integration_launch/package.xml @@ -22,7 +22,7 @@ vehicle_launch ament_lint_auto - ament_lint_common + autoware_lint_common ament_cmake diff --git a/localization_launch/launch/util/util.launch.py b/localization_launch/launch/util/util.launch.py index 055eca0450..b6f66fa19e 100644 --- a/localization_launch/launch/util/util.launch.py +++ b/localization_launch/launch/util/util.launch.py @@ -26,66 +26,55 @@ def launch_setup(context, *args, **kwargs): # https://github.com/ros2/launch_ros/issues/156 def load_composable_node_param(param_path): - with open(LaunchConfiguration(param_path).perform(context), 'r') as f: - return yaml.safe_load(f)['/**']['ros__parameters'] + with open(LaunchConfiguration(param_path).perform(context), "r") as f: + return yaml.safe_load(f)["/**"]["ros__parameters"] crop_box_component = ComposableNode( - package='pointcloud_preprocessor', - plugin='pointcloud_preprocessor::CropBoxFilterComponent', - name='crop_box_filter_measurement_range', + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::CropBoxFilterComponent", + name="crop_box_filter_measurement_range", remappings=[ - ('input', LaunchConfiguration('input_sensor_points_topic')), - ('output', - LaunchConfiguration('output_measurement_range_sensor_points_topic')), + ("input", LaunchConfiguration("input_sensor_points_topic")), + ("output", LaunchConfiguration("output_measurement_range_sensor_points_topic")), ], parameters=[ - load_composable_node_param('crop_box_filter_measurement_range_param_path'), + load_composable_node_param("crop_box_filter_measurement_range_param_path"), ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) voxel_grid_downsample_component = ComposableNode( - package='pointcloud_preprocessor', - plugin='pointcloud_preprocessor::VoxelGridDownsampleFilterComponent', - name='voxel_grid_downsample_filter', + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", + name="voxel_grid_downsample_filter", remappings=[ - ('input', - LaunchConfiguration('output_measurement_range_sensor_points_topic')), - ('output', - LaunchConfiguration('output_voxel_grid_downsample_sensor_points_topic')), + ("input", LaunchConfiguration("output_measurement_range_sensor_points_topic")), + ("output", LaunchConfiguration("output_voxel_grid_downsample_sensor_points_topic")), ], - parameters=[load_composable_node_param('voxel_grid_downsample_filter_param_path')], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + parameters=[load_composable_node_param("voxel_grid_downsample_filter_param_path")], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) random_downsample_component = ComposableNode( - package='pointcloud_preprocessor', - plugin='pointcloud_preprocessor::VoxelGridDownsampleFilterComponent', - name='random_downsample_filter', + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", + name="random_downsample_filter", remappings=[ - ('input', - LaunchConfiguration('output_voxel_grid_downsample_sensor_points_topic')), - ('output', - LaunchConfiguration('output_downsample_sensor_points_topic')), + ("input", LaunchConfiguration("output_voxel_grid_downsample_sensor_points_topic")), + ("output", LaunchConfiguration("output_downsample_sensor_points_topic")), ], - parameters=[ - load_composable_node_param('random_downsample_filter_param_path') - ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + parameters=[load_composable_node_param("random_downsample_filter_param_path")], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - composable_nodes = [crop_box_component, - voxel_grid_downsample_component, - random_downsample_component] + composable_nodes = [ + crop_box_component, + voxel_grid_downsample_component, + random_downsample_component, + ] load_composable_nodes = LoadComposableNodes( - condition=LaunchConfigurationNotEquals('container', ''), + condition=LaunchConfigurationNotEquals("container", ""), composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration('container'), + target_container=LaunchConfiguration("container"), ) return [load_composable_nodes] @@ -99,59 +88,48 @@ def add_launch_arg(name: str, default_value=None, description=None): launch_arguments.append(arg) add_launch_arg( - 'crop_box_filter_measurement_range_param_path', + "crop_box_filter_measurement_range_param_path", [ - FindPackageShare('localization_launch'), - '/config/crop_box_filter_measurement_range.param.yaml' + FindPackageShare("localization_launch"), + "/config/crop_box_filter_measurement_range.param.yaml", ], - 'path to the parameter file of crop_box_filter_measurement_range' + "path to the parameter file of crop_box_filter_measurement_range", ) add_launch_arg( - 'voxel_grid_downsample_filter_param_path', - [ - FindPackageShare('localization_launch'), - '/config/voxel_grid_filter.param.yaml' - ], - 'path to the parameter file of voxel_grid_downsample_filter' + "voxel_grid_downsample_filter_param_path", + [FindPackageShare("localization_launch"), "/config/voxel_grid_filter.param.yaml"], + "path to the parameter file of voxel_grid_downsample_filter", ) add_launch_arg( - 'random_downsample_filter_param_path', - [ - FindPackageShare('localization_launch'), - '/config/random_downsample_filter.param.yaml' - ], - 'path to the parameter file of random_downsample_filter' + "random_downsample_filter_param_path", + [FindPackageShare("localization_launch"), "/config/random_downsample_filter.param.yaml"], + "path to the parameter file of random_downsample_filter", ) - add_launch_arg('use_intra_process', 'true', 'use ROS2 component container communication') + add_launch_arg("use_intra_process", "true", "use ROS2 component container communication") add_launch_arg( - 'container', - '/sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container', - 'container name' + "container", + "/sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container", + "container name", ) add_launch_arg( - 'input_sensor_points_topic', - '/sensing/lidar/top/rectified/pointcloud', - 'input topic name for raw pointcloud' + "input_sensor_points_topic", + "/sensing/lidar/top/rectified/pointcloud", + "input topic name for raw pointcloud", ) add_launch_arg( - 'output_measurement_range_sensor_points_topic', - 'measurement_range/pointcloud', - 'output topic name for crop box filter' + "output_measurement_range_sensor_points_topic", + "measurement_range/pointcloud", + "output topic name for crop box filter", ) add_launch_arg( - 'output_voxel_grid_downsample_sensor_points_topic', - 'voxel_grid_downsample/pointcloud', - 'output topic name for voxel grid downsample filter' + "output_voxel_grid_downsample_sensor_points_topic", + "voxel_grid_downsample/pointcloud", + "output topic name for voxel grid downsample filter", ) add_launch_arg( - 'output_downsample_sensor_points_topic', - 'downsample/pointcloud', - 'output topic name for downsample filter. this is final output' + "output_downsample_sensor_points_topic", + "downsample/pointcloud", + "output topic name for downsample filter. this is final output", ) - return launch.LaunchDescription( - launch_arguments + - [ - OpaqueFunction(function=launch_setup) - ] - ) + return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) diff --git a/localization_launch/package.xml b/localization_launch/package.xml index bd01526b20..a6dbe359ce 100644 --- a/localization_launch/package.xml +++ b/localization_launch/package.xml @@ -19,7 +19,7 @@ topic_tools ament_lint_auto - ament_lint_common + autoware_lint_common ament_cmake diff --git a/map_launch/launch/map.launch.py b/map_launch/launch/map.launch.py index 804e118297..910b9a3bd6 100644 --- a/map_launch/launch/map.launch.py +++ b/map_launch/launch/map.launch.py @@ -27,113 +27,115 @@ def generate_launch_description(): map_hash_generator = Node( - package='map_loader', - executable='map_hash_generator', - name='map_hash_generator', + package="map_loader", + executable="map_hash_generator", + name="map_hash_generator", parameters=[ { - 'lanelet2_map_path': LaunchConfiguration('lanelet2_map_path'), + "lanelet2_map_path": LaunchConfiguration("lanelet2_map_path"), } ], ) lanelet2_map_loader = ComposableNode( - package='map_loader', - plugin='Lanelet2MapLoaderNode', - name='lanelet2_map_loader', - remappings=[('output/lanelet2_map', 'vector_map')], + package="map_loader", + plugin="Lanelet2MapLoaderNode", + name="lanelet2_map_loader", + remappings=[("output/lanelet2_map", "vector_map")], parameters=[ { - 'center_line_resolution': 5.0, - 'lanelet2_map_path': LaunchConfiguration('lanelet2_map_path'), + "center_line_resolution": 5.0, + "lanelet2_map_path": LaunchConfiguration("lanelet2_map_path"), } ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) lanelet2_map_visualization = ComposableNode( - package='map_loader', - plugin='Lanelet2MapVisualizationNode', - name='lanelet2_map_visualization', - remappings=[('input/lanelet2_map', 'vector_map'), - ('output/lanelet2_map_marker', 'vector_map_marker')], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + package="map_loader", + plugin="Lanelet2MapVisualizationNode", + name="lanelet2_map_visualization", + remappings=[ + ("input/lanelet2_map", "vector_map"), + ("output/lanelet2_map_marker", "vector_map_marker"), + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) pointcloud_map_loader = ComposableNode( - package='map_loader', - plugin='PointCloudMapLoaderNode', - name='pointcloud_map_loader', - remappings=[('output/pointcloud_map', 'pointcloud_map')], + package="map_loader", + plugin="PointCloudMapLoaderNode", + name="pointcloud_map_loader", + remappings=[("output/pointcloud_map", "pointcloud_map")], parameters=[ - { - 'pcd_paths_or_directory': ['[', LaunchConfiguration('pointcloud_map_path'), ']'] - } + {"pcd_paths_or_directory": ["[", LaunchConfiguration("pointcloud_map_path"), "]"]} ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) map_tf_generator = ComposableNode( - package='map_tf_generator', - plugin='MapTFGeneratorNode', - name='map_tf_generator', + package="map_tf_generator", + plugin="MapTFGeneratorNode", + name="map_tf_generator", parameters=[ { - 'map_frame': 'map', - 'viewer_frame': 'viewer', + "map_frame": "map", + "viewer_frame": "viewer", } ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) container = ComposableNodeContainer( - name='map_container', - namespace='', - package='rclcpp_components', - executable=LaunchConfiguration('container_executable'), + name="map_container", + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ lanelet2_map_loader, lanelet2_map_visualization, pointcloud_map_loader, map_tf_generator, ], - output='screen', + output="screen", ) def add_launch_arg(name: str, default_value=None, description=None): return DeclareLaunchArgument(name, default_value=default_value, description=description) - return launch.LaunchDescription([ - add_launch_arg('map_path', '', 'path to map directory'), - add_launch_arg('lanelet2_map_path', [ - LaunchConfiguration('map_path'), '/lanelet2_map.osm'], - 'path to lanelet2 map file'), - add_launch_arg('pointcloud_map_path', [ - LaunchConfiguration('map_path'), '/pointcloud_map.pcd'], - 'path to pointcloud map file'), - add_launch_arg('use_intra_process', 'false', 'use ROS2 component container communication'), - add_launch_arg('use_multithread', 'false', 'use multithread'), - SetLaunchConfiguration( - 'container_executable', - 'component_container', - condition=UnlessCondition(LaunchConfiguration('use_multithread')) - ), - SetLaunchConfiguration( - 'container_executable', - 'component_container_mt', - condition=IfCondition(LaunchConfiguration('use_multithread')) - ), - GroupAction([ - PushRosNamespace('map'), - container, - map_hash_generator, - ]) - ]) + return launch.LaunchDescription( + [ + add_launch_arg("map_path", "", "path to map directory"), + add_launch_arg( + "lanelet2_map_path", + [LaunchConfiguration("map_path"), "/lanelet2_map.osm"], + "path to lanelet2 map file", + ), + add_launch_arg( + "pointcloud_map_path", + [LaunchConfiguration("map_path"), "/pointcloud_map.pcd"], + "path to pointcloud map file", + ), + add_launch_arg( + "use_intra_process", "false", "use ROS2 component container communication" + ), + add_launch_arg("use_multithread", "false", "use multithread"), + SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ), + SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ), + GroupAction( + [ + PushRosNamespace("map"), + container, + map_hash_generator, + ] + ), + ] + ) diff --git a/map_launch/package.xml b/map_launch/package.xml index 9faf46ebd9..b8f7613344 100644 --- a/map_launch/package.xml +++ b/map_launch/package.xml @@ -14,7 +14,7 @@ map_tf_generator ament_lint_auto - ament_lint_common + autoware_lint_common ament_cmake 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 2600c0c2b0..d048743b80 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 @@ -32,45 +32,43 @@ def generate_launch_description(): def add_launch_arg(name: str, default_value=None, description=None): # a default_value of None is equivalent to not passing that kwarg at all - launch_arguments.append(DeclareLaunchArgument( - name, default_value=default_value, description=description)) + launch_arguments.append( + DeclareLaunchArgument(name, default_value=default_value, description=description) + ) - 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') + 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]') + 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') - - add_launch_arg('use_intra_process', 'False') - add_launch_arg('use_multithread', 'False') + 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") + + add_launch_arg("use_intra_process", "False") + add_launch_arg("use_multithread", "False") def create_parameter_dict(*args): result = {} @@ -79,98 +77,125 @@ def create_parameter_dict(*args): return result container = ComposableNodeContainer( - name='traffic_light_node_container', - namespace='/perception/traffic_light_recognition', - package='rclcpp_components', - executable=LaunchConfiguration('container_executable'), + name="traffic_light_node_container", + namespace="/perception/traffic_light_recognition", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ ComposableNode( - package='image_transport_decompressor', - plugin='image_preprocessor::ImageTransportDecompressor', - name='traffic_light_image_decompressor', - parameters=[{'encoding': 'rgb8'}], - remappings=[('~/input/compressed_image', - [LaunchConfiguration('input/image'), '/compressed']), - ('~/output/raw_image', LaunchConfiguration('input/image'))], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + package="image_transport_decompressor", + plugin="image_preprocessor::ImageTransportDecompressor", + name="traffic_light_image_decompressor", + parameters=[{"encoding": "rgb8"}], + remappings=[ + ( + "~/input/compressed_image", + [LaunchConfiguration("input/image"), "/compressed"], + ), + ("~/output/raw_image", LaunchConfiguration("input/image")), + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], ), 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')], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + 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"), + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], ), 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'), - ('~/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/theora', 'debug/rois/theora')], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) + 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"), + ("~/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/theora", "debug/rois/theora"), + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ), ], - output='both', + 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') + 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', + 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')], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + remappings=[ + ("~/input/image", LaunchConfiguration("input/image")), + ("~/input/rois", "rough/rois"), + ("~/output/rois", "rois"), + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], ), ], target_container=container, - condition=launch.conditions.IfCondition(LaunchConfiguration('enable_fine_detection')), + condition=launch.conditions.IfCondition(LaunchConfiguration("enable_fine_detection")), ) set_container_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container', - condition=UnlessCondition(LaunchConfiguration('use_multithread')) + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), ) set_container_mt_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container_mt', - condition=IfCondition(LaunchConfiguration('use_multithread')) + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), ) - return LaunchDescription([ - *launch_arguments, - set_container_executable, - set_container_mt_executable, - container, - loader, - ]) + return LaunchDescription( + [ + *launch_arguments, + set_container_executable, + set_container_mt_executable, + container, + loader, + ] + ) diff --git a/perception_launch/package.xml b/perception_launch/package.xml index 35ed04f900..d54c251440 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -28,7 +28,7 @@ traffic_light_visualization ament_lint_auto - ament_lint_common + autoware_lint_common ament_cmake diff --git a/planning_launch/launch/mission_planning/mission_planning.launch.py b/planning_launch/launch/mission_planning/mission_planning.launch.py index 4f5fb52afd..cc3952f93b 100644 --- a/planning_launch/launch/mission_planning/mission_planning.launch.py +++ b/planning_launch/launch/mission_planning/mission_planning.launch.py @@ -21,50 +21,53 @@ def generate_launch_description(): container = ComposableNodeContainer( - name='mission_planning_container', - namespace='', - package='rclcpp_components', - executable='component_container', + name="mission_planning_container", + namespace="", + package="rclcpp_components", + executable="component_container", composable_node_descriptions=[ ComposableNode( - package='mission_planner', - plugin='mission_planner::MissionPlannerLanelet2', - name='mission_planner', + package="mission_planner", + plugin="mission_planner::MissionPlannerLanelet2", + name="mission_planner", remappings=[ - ('input/vector_map', '/map/vector_map'), - ('input/goal_pose', '/planning/mission_planning/goal'), - ('input/checkpoint', '/planning/mission_planning/checkpoint'), - ('output/route', '/planning/mission_planning/route'), - ('debug/route_marker', - '/planning/mission_planning/route_marker'), + ("input/vector_map", "/map/vector_map"), + ("input/goal_pose", "/planning/mission_planning/goal"), + ("input/checkpoint", "/planning/mission_planning/checkpoint"), + ("output/route", "/planning/mission_planning/route"), + ("debug/route_marker", "/planning/mission_planning/route_marker"), ], parameters=[ { - 'map_frame': 'map', - 'base_link_frame': 'base_link', + "map_frame": "map", + "base_link_frame": "base_link", } ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], ), ComposableNode( - package='mission_planner', - plugin='mission_planner::GoalPoseVisualizer', - name='goal_pose_visualizer', + package="mission_planner", + plugin="mission_planner::GoalPoseVisualizer", + name="goal_pose_visualizer", remappings=[ - ('input/route', '/planning/mission_planning/route'), - ('output/goal_pose', - '/planning/mission_planning/echo_back_goal_pose'), + ("input/route", "/planning/mission_planning/route"), + ("output/goal_pose", "/planning/mission_planning/echo_back_goal_pose"), + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) + ), ], ) - return launch.LaunchDescription([ - DeclareLaunchArgument('use_intra_process', default_value='false', - description='use ROS2 component container communication'), - container - ]) + return launch.LaunchDescription( + [ + DeclareLaunchArgument( + "use_intra_process", + default_value="false", + description="use ROS2 component container communication", + ), + container, + ] + ) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 7a035f93a0..da2d221ad7 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -31,122 +31,132 @@ def generate_launch_description(): # behavior path planner side_shift_param_path = os.path.join( - get_package_share_directory('planning_launch'), - 'config', - 'scenario_planning', - 'lane_driving', - 'behavior_planning', - 'behavior_path_planner', - 'side_shift', - 'side_shift.param.yaml', + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_path_planner", + "side_shift", + "side_shift.param.yaml", ) - with open(side_shift_param_path, 'r') as f: - side_shift_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(side_shift_param_path, "r") as f: + side_shift_param = yaml.safe_load(f)["/**"]["ros__parameters"] avoidance_param_path = os.path.join( - get_package_share_directory('planning_launch'), - 'config', - 'scenario_planning', - 'lane_driving', - 'behavior_planning', - 'behavior_path_planner', - 'avoidance', - 'avoidance.param.yaml', + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_path_planner", + "avoidance", + "avoidance.param.yaml", ) - with open(avoidance_param_path, 'r') as f: - avoidance_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(avoidance_param_path, "r") as f: + avoidance_param = yaml.safe_load(f)["/**"]["ros__parameters"] lane_change_param_path = os.path.join( - get_package_share_directory('planning_launch'), - 'config', - 'scenario_planning', - 'lane_driving', - 'behavior_planning', - 'behavior_path_planner', - 'lane_change', - 'lane_change.param.yaml', + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_path_planner", + "lane_change", + "lane_change.param.yaml", ) - with open(lane_change_param_path, 'r') as f: - lane_change_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(lane_change_param_path, "r") as f: + lane_change_param = yaml.safe_load(f)["/**"]["ros__parameters"] lane_following_param_path = os.path.join( - get_package_share_directory('planning_launch'), - 'config', - 'scenario_planning', - 'lane_driving', - 'behavior_planning', - 'behavior_path_planner', - 'lane_following', - 'lane_following.param.yaml', + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_path_planner", + "lane_following", + "lane_following.param.yaml", ) - with open(lane_following_param_path, 'r') as f: - lane_following_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(lane_following_param_path, "r") as f: + lane_following_param = yaml.safe_load(f)["/**"]["ros__parameters"] pull_over_param_path = os.path.join( - get_package_share_directory('planning_launch'), - 'config', - 'scenario_planning', - 'lane_driving', - 'behavior_planning', - 'behavior_path_planner', - 'pull_over', - 'pull_over.param.yaml', + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_path_planner", + "pull_over", + "pull_over.param.yaml", ) - with open(pull_over_param_path, 'r') as f: - pull_over_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(pull_over_param_path, "r") as f: + pull_over_param = yaml.safe_load(f)["/**"]["ros__parameters"] pull_out_param_path = os.path.join( - get_package_share_directory('planning_launch'), - 'config', - 'scenario_planning', - 'lane_driving', - 'behavior_planning', - 'behavior_path_planner', - 'pull_out', - 'pull_out.param.yaml', + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_path_planner", + "pull_out", + "pull_out.param.yaml", ) - with open(pull_out_param_path, 'r') as f: - pull_out_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(pull_out_param_path, "r") as f: + pull_out_param = yaml.safe_load(f)["/**"]["ros__parameters"] behavior_path_planner_param_path = os.path.join( - get_package_share_directory('planning_launch'), - 'config', - 'scenario_planning', - 'lane_driving', - 'behavior_planning', - 'behavior_path_planner', - 'behavior_path_planner.param.yaml', + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_path_planner", + "behavior_path_planner.param.yaml", ) - with open(behavior_path_planner_param_path, 'r') as f: - behavior_path_planner_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(behavior_path_planner_param_path, "r") as f: + behavior_path_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] behavior_path_planner_component = ComposableNode( - package='behavior_path_planner', - plugin='behavior_path_planner::BehaviorPathPlannerNode', - name='behavior_path_planner', - namespace='', + package="behavior_path_planner", + plugin="behavior_path_planner::BehaviorPathPlannerNode", + name="behavior_path_planner", + namespace="", remappings=[ - ('~/input/route', LaunchConfiguration('input_route_topic_name')), - ('~/input/vector_map', LaunchConfiguration('map_topic_name')), - ('~/input/perception', '/perception/object_recognition/objects'), - ('~/input/velocity', '/localization/twist'), - ('~/input/external_approval', - '/planning/scenario_planning/lane_driving/behavior_planning/' - 'behavior_path_planner/path_change_approval'), - ('~/input/force_approval', - '/planning/scenario_planning/lane_driving/behavior_planning/' - 'behavior_path_planner/path_change_force'), - ('~/output/path', 'path_with_lane_id'), - ('~/output/ready', - '/planning/scenario_planning/lane_driving/behavior_planning/' - 'behavior_path_planner/ready_module'), - ('~/output/running', - '/planning/scenario_planning/lane_driving/behavior_planning/' - 'behavior_path_planner/running_modules'), - ('~/output/force_available', - '/planning/scenario_planning/lane_driving/behavior_planning/' - 'behavior_path_planner/force_available'), - ('~/output/turn_signal_cmd', '/planning/turn_signal_decider/turn_signal_cmd'), + ("~/input/route", LaunchConfiguration("input_route_topic_name")), + ("~/input/vector_map", LaunchConfiguration("map_topic_name")), + ("~/input/perception", "/perception/object_recognition/objects"), + ("~/input/velocity", "/localization/twist"), + ( + "~/input/external_approval", + "/planning/scenario_planning/lane_driving/behavior_planning/" + "behavior_path_planner/path_change_approval", + ), + ( + "~/input/force_approval", + "/planning/scenario_planning/lane_driving/behavior_planning/" + "behavior_path_planner/path_change_force", + ), + ("~/output/path", "path_with_lane_id"), + ( + "~/output/ready", + "/planning/scenario_planning/lane_driving/behavior_planning/" + "behavior_path_planner/ready_module", + ), + ( + "~/output/running", + "/planning/scenario_planning/lane_driving/behavior_planning/" + "behavior_path_planner/running_modules", + ), + ( + "~/output/force_available", + "/planning/scenario_planning/lane_driving/behavior_planning/" + "behavior_path_planner/force_available", + ), + ("~/output/turn_signal_cmd", "/planning/turn_signal_decider/turn_signal_cmd"), ], parameters=[ side_shift_param, @@ -157,121 +167,124 @@ def generate_launch_description(): pull_out_param, behavior_path_planner_param, { - 'bt_tree_config_path': - [FindPackageShare('behavior_path_planner'), - '/config/behavior_path_planner_tree.xml'], - 'planning_hz': 10.0, - } - ], - extra_arguments=[ - {'use_intra_process_comms': LaunchConfiguration('use_intra_process')} + "bt_tree_config_path": [ + FindPackageShare("behavior_path_planner"), + "/config/behavior_path_planner_tree.xml", + ], + "planning_hz": 10.0, + }, ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) # behavior velocity planner blind_spot_param_path = os.path.join( - get_package_share_directory('behavior_velocity_planner'), - 'config', - 'blind_spot.param.yaml', + get_package_share_directory("behavior_velocity_planner"), + "config", + "blind_spot.param.yaml", ) - with open(blind_spot_param_path, 'r') as f: - blind_spot_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(blind_spot_param_path, "r") as f: + blind_spot_param = yaml.safe_load(f)["/**"]["ros__parameters"] crosswalk_param_path = os.path.join( - get_package_share_directory('behavior_velocity_planner'), - 'config', - 'crosswalk.param.yaml', + get_package_share_directory("behavior_velocity_planner"), + "config", + "crosswalk.param.yaml", ) - with open(crosswalk_param_path, 'r') as f: - crosswalk_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(crosswalk_param_path, "r") as f: + crosswalk_param = yaml.safe_load(f)["/**"]["ros__parameters"] detection_area_param_path = os.path.join( - get_package_share_directory('behavior_velocity_planner'), - 'config', - 'detection_area.param.yaml', + get_package_share_directory("behavior_velocity_planner"), + "config", + "detection_area.param.yaml", ) - with open(detection_area_param_path, 'r') as f: - detection_area_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(detection_area_param_path, "r") as f: + detection_area_param = yaml.safe_load(f)["/**"]["ros__parameters"] intersection_param_path = os.path.join( - get_package_share_directory('behavior_velocity_planner'), - 'config', - 'intersection.param.yaml', + get_package_share_directory("behavior_velocity_planner"), + "config", + "intersection.param.yaml", ) - with open(intersection_param_path, 'r') as f: - intersection_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(intersection_param_path, "r") as f: + intersection_param = yaml.safe_load(f)["/**"]["ros__parameters"] stop_line_param_path = os.path.join( - get_package_share_directory('behavior_velocity_planner'), - 'config', - 'stop_line.param.yaml', + get_package_share_directory("behavior_velocity_planner"), + "config", + "stop_line.param.yaml", ) - with open(stop_line_param_path, 'r') as f: - stop_line_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(stop_line_param_path, "r") as f: + stop_line_param = yaml.safe_load(f)["/**"]["ros__parameters"] traffic_light_param_path = os.path.join( - get_package_share_directory('behavior_velocity_planner'), - 'config', - 'traffic_light.param.yaml', + get_package_share_directory("behavior_velocity_planner"), + "config", + "traffic_light.param.yaml", ) - with open(traffic_light_param_path, 'r') as f: - traffic_light_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(traffic_light_param_path, "r") as f: + traffic_light_param = yaml.safe_load(f)["/**"]["ros__parameters"] virtual_traffic_light_param_path = os.path.join( - get_package_share_directory('behavior_velocity_planner'), - 'config', - 'virtual_traffic_light.param.yaml', + get_package_share_directory("behavior_velocity_planner"), + "config", + "virtual_traffic_light.param.yaml", ) - with open(virtual_traffic_light_param_path, 'r') as f: - virtual_traffic_light_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(virtual_traffic_light_param_path, "r") as f: + virtual_traffic_light_param = yaml.safe_load(f)["/**"]["ros__parameters"] occlusion_spot_param_path = os.path.join( - get_package_share_directory('behavior_velocity_planner'), - 'config', - 'occlusion_spot.param.yaml', + get_package_share_directory("behavior_velocity_planner"), + "config", + "occlusion_spot.param.yaml", ) - with open(occlusion_spot_param_path, 'r') as f: - occlusion_spot_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(occlusion_spot_param_path, "r") as f: + occlusion_spot_param = yaml.safe_load(f)["/**"]["ros__parameters"] behavior_velocity_planner_component = ComposableNode( - package='behavior_velocity_planner', - plugin='behavior_velocity_planner::BehaviorVelocityPlannerNode', - name='behavior_velocity_planner', - namespace='', + package="behavior_velocity_planner", + plugin="behavior_velocity_planner::BehaviorVelocityPlannerNode", + name="behavior_velocity_planner", + namespace="", remappings=[ - ('~/input/path_with_lane_id', 'path_with_lane_id'), - ('~/input/vector_map', '/map/vector_map'), - ('~/input/vehicle_velocity', '/localization/twist'), - ('~/input/dynamic_objects', '/perception/object_recognition/objects'), - ('~/input/no_ground_pointcloud', '/sensing/lidar/no_ground/pointcloud'), - ('~/input/traffic_light_states', - '/perception/traffic_light_recognition/traffic_light_states'), - ('~/input/external_traffic_light_states', - '/external/traffic_light_recognition/traffic_light_states'), - ('~/input/virtual_traffic_light_states', - '/awapi/tmp/virtual_traffic_light_states'), - ('~/input/occupancy_grid', '/sensing/lidar/occupancy_grid'), - ('~/output/path', 'path'), - ('~/output/stop_reasons', - '/planning/scenario_planning/status/stop_reasons'), - ('~/output/infrastructure_commands', - '/planning/scenario_planning/status/infrastructure_commands'), - ('~/output/traffic_light_state', 'debug/traffic_light_state'), + ("~/input/path_with_lane_id", "path_with_lane_id"), + ("~/input/vector_map", "/map/vector_map"), + ("~/input/vehicle_velocity", "/localization/twist"), + ("~/input/dynamic_objects", "/perception/object_recognition/objects"), + ("~/input/no_ground_pointcloud", "/sensing/lidar/no_ground/pointcloud"), + ( + "~/input/traffic_light_states", + "/perception/traffic_light_recognition/traffic_light_states", + ), + ( + "~/input/external_traffic_light_states", + "/external/traffic_light_recognition/traffic_light_states", + ), + ("~/input/virtual_traffic_light_states", "/awapi/tmp/virtual_traffic_light_states"), + ("~/input/occupancy_grid", "/sensing/lidar/occupancy_grid"), + ("~/output/path", "path"), + ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), + ( + "~/output/infrastructure_commands", + "/planning/scenario_planning/status/infrastructure_commands", + ), + ("~/output/traffic_light_state", "debug/traffic_light_state"), ], parameters=[ { - 'launch_stop_line': True, - 'launch_crosswalk': True, - 'launch_traffic_light': True, - 'launch_intersection': True, - 'launch_blind_spot': True, - 'launch_detection_area': True, - 'launch_virtual_traffic_light': True, - 'launch_occlusion_spot': True, - 'forward_path_length': 1000.0, - 'backward_path_length': 5.0, - 'max_accel': -2.8, - 'delay_response_time': 1.3 + "launch_stop_line": True, + "launch_crosswalk": True, + "launch_traffic_light": True, + "launch_intersection": True, + "launch_blind_spot": True, + "launch_detection_area": True, + "launch_virtual_traffic_light": True, + "launch_occlusion_spot": True, + "forward_path_length": 1000.0, + "backward_path_length": 5.0, + "max_accel": -2.8, + "delay_response_time": 1.3, }, blind_spot_param, crosswalk_param, @@ -280,59 +293,57 @@ def generate_launch_description(): stop_line_param, traffic_light_param, virtual_traffic_light_param, - occlusion_spot_param + occlusion_spot_param, ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) container = ComposableNodeContainer( - name='behavior_planning_container', - namespace='', - package='rclcpp_components', - executable=LaunchConfiguration('container_executable'), + name="behavior_planning_container", + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ behavior_path_planner_component, behavior_velocity_planner_component, ], - output='screen', + output="screen", ) set_container_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container', - condition=UnlessCondition(LaunchConfiguration('use_multithread')), + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), ) set_container_mt_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container_mt', - condition=IfCondition(LaunchConfiguration('use_multithread')), + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), ) - return launch.LaunchDescription([ - DeclareLaunchArgument( - 'input_route_topic_name', - default_value='/planning/mission_planning/route'), - DeclareLaunchArgument( - 'map_topic_name', - default_value='/map/vector_map' - ), - DeclareLaunchArgument( - 'use_intra_process', - default_value='false' - ), - DeclareLaunchArgument( - 'use_multithread', - default_value='false' - ), - set_container_executable, - set_container_mt_executable, - container, - ExecuteProcess( - cmd=['ros2', 'topic', 'pub', - '/planning/scenario_planning/lane_driving/behavior_planning/' - 'behavior_path_planner/path_change_approval', - 'autoware_planning_msgs/msg/Approval', '{approval: true}', - '-r', '10']), - ]) + return launch.LaunchDescription( + [ + DeclareLaunchArgument( + "input_route_topic_name", default_value="/planning/mission_planning/route" + ), + DeclareLaunchArgument("map_topic_name", default_value="/map/vector_map"), + DeclareLaunchArgument("use_intra_process", default_value="false"), + DeclareLaunchArgument("use_multithread", default_value="false"), + set_container_executable, + set_container_mt_executable, + container, + ExecuteProcess( + cmd=[ + "ros2", + "topic", + "pub", + "/planning/scenario_planning/lane_driving/behavior_planning/" + "behavior_path_planner/path_change_approval", + "autoware_planning_msgs/msg/Approval", + "{approval: true}", + "-r", + "10", + ] + ), + ] + ) diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index d3a3f30493..79a0c31a94 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -30,207 +30,191 @@ def generate_launch_description(): # planning common param path common_param_path = os.path.join( - get_package_share_directory('planning_launch'), - 'config', - 'scenario_planning', - 'common', - 'common.param.yaml', + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "common", + "common.param.yaml", ) - with open(common_param_path, 'r') as f: - common_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(common_param_path, "r") as f: + common_param = yaml.safe_load(f)["/**"]["ros__parameters"] # obstacle avoidance planner obstacle_avoidance_planner_param_path = os.path.join( - get_package_share_directory('planning_launch'), - 'config', - 'scenario_planning', - 'lane_driving', - 'motion_planning', - 'obstacle_avoidance_planner', - 'obstacle_avoidance_planner.param.yaml', + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "motion_planning", + "obstacle_avoidance_planner", + "obstacle_avoidance_planner.param.yaml", ) - with open(obstacle_avoidance_planner_param_path, 'r') as f: - obstacle_avoidance_planner_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(obstacle_avoidance_planner_param_path, "r") as f: + obstacle_avoidance_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] obstacle_avoidance_planner_component = ComposableNode( - package='obstacle_avoidance_planner', - plugin='ObstacleAvoidancePlanner', - name='obstacle_avoidance_planner', - namespace='', + package="obstacle_avoidance_planner", + plugin="ObstacleAvoidancePlanner", + name="obstacle_avoidance_planner", + namespace="", remappings=[ - ('~/input/objects', '/perception/object_recognition/objects'), - ('~/input/path', LaunchConfiguration('input_path_topic')), - ('~/output/path', 'obstacle_avoidance_planner/trajectory'), + ("~/input/objects", "/perception/object_recognition/objects"), + ("~/input/path", LaunchConfiguration("input_path_topic")), + ("~/output/path", "obstacle_avoidance_planner/trajectory"), ], parameters=[ obstacle_avoidance_planner_param, - {'is_showing_debug_info': False}, - {'is_stopping_if_outside_drivable_area': True}, - ], - extra_arguments=[ - {'use_intra_process_comms': LaunchConfiguration('use_intra_process')} + {"is_showing_debug_info": False}, + {"is_stopping_if_outside_drivable_area": True}, ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) # surround obstacle checker surround_obstacle_checker_param_path = os.path.join( - get_package_share_directory('planning_launch'), - 'config', - 'scenario_planning', - 'lane_driving', - 'motion_planning', - 'surround_obstacle_checker', - 'surround_obstacle_checker.param.yaml', + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "motion_planning", + "surround_obstacle_checker", + "surround_obstacle_checker.param.yaml", ) - with open(surround_obstacle_checker_param_path, 'r') as f: - surround_obstacle_checker_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(surround_obstacle_checker_param_path, "r") as f: + surround_obstacle_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] surround_obstacle_checker_component = ComposableNode( - package='surround_obstacle_checker', - plugin='SurroundObstacleCheckerNode', - name='surround_obstacle_checker', - namespace='', + package="surround_obstacle_checker", + plugin="SurroundObstacleCheckerNode", + name="surround_obstacle_checker", + namespace="", remappings=[ - ('~/output/no_start_reason', - '/planning/scenario_planning/status/no_start_reason'), - ('~/output/stop_reasons', - '/planning/scenario_planning/status/stop_reasons'), - ('~/output/trajectory', 'surround_obstacle_checker/trajectory'), - ('~/input/pointcloud', '/sensing/lidar/no_ground/pointcloud'), - ('~/input/objects', '/perception/object_recognition/objects'), - ('~/input/twist', '/localization/twist'), - ('~/input/trajectory', 'obstacle_avoidance_planner/trajectory'), + ("~/output/no_start_reason", "/planning/scenario_planning/status/no_start_reason"), + ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), + ("~/output/trajectory", "surround_obstacle_checker/trajectory"), + ("~/input/pointcloud", "/sensing/lidar/no_ground/pointcloud"), + ("~/input/objects", "/perception/object_recognition/objects"), + ("~/input/twist", "/localization/twist"), + ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), ], parameters=[ surround_obstacle_checker_param, ], - extra_arguments=[ - {'use_intra_process_comms': LaunchConfiguration('use_intra_process')} - ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) # relay relay_component = ComposableNode( - package='topic_tools', - plugin='topic_tools::RelayNode', - name='skip_surround_obstacle_check_relay', - namespace='', - parameters=[{ - 'input_topic': 'obstacle_avoidance_planner/trajectory', - 'output_topic': 'surround_obstacle_checker/trajectory', - 'type': 'autoware_planning_msgs/msg/Trajectory', - }], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + package="topic_tools", + plugin="topic_tools::RelayNode", + name="skip_surround_obstacle_check_relay", + namespace="", + parameters=[ + { + "input_topic": "obstacle_avoidance_planner/trajectory", + "output_topic": "surround_obstacle_checker/trajectory", + "type": "autoware_planning_msgs/msg/Trajectory", + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) # obstacle stop planner obstacle_stop_planner_param_path = os.path.join( - get_package_share_directory('planning_launch'), - 'config', - 'scenario_planning', - 'lane_driving', - 'motion_planning', - 'obstacle_stop_planner', - 'obstacle_stop_planner.param.yaml', + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "motion_planning", + "obstacle_stop_planner", + "obstacle_stop_planner.param.yaml", ) obstacle_stop_planner_acc_param_path = os.path.join( - get_package_share_directory('planning_launch'), - 'config', - 'scenario_planning', - 'lane_driving', - 'motion_planning', - 'obstacle_stop_planner', - 'adaptive_cruise_control.param.yaml', + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "motion_planning", + "obstacle_stop_planner", + "adaptive_cruise_control.param.yaml", ) - with open(obstacle_stop_planner_param_path, 'r') as f: - obstacle_stop_planner_param = yaml.safe_load(f)['/**']['ros__parameters'] - with open(obstacle_stop_planner_acc_param_path, 'r') as f: - obstacle_stop_planner_acc_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(obstacle_stop_planner_param_path, "r") as f: + obstacle_stop_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] + with open(obstacle_stop_planner_acc_param_path, "r") as f: + obstacle_stop_planner_acc_param = yaml.safe_load(f)["/**"]["ros__parameters"] obstacle_stop_planner_component = ComposableNode( - package='obstacle_stop_planner', - plugin='motion_planning::ObstacleStopPlannerNode', - name='obstacle_stop_planner', - namespace='', + package="obstacle_stop_planner", + plugin="motion_planning::ObstacleStopPlannerNode", + name="obstacle_stop_planner", + namespace="", remappings=[ - ('~/output/stop_reason', - '/planning/scenario_planning/status/stop_reason'), - ('~/output/stop_reasons', - '/planning/scenario_planning/status/stop_reasons'), - ('~/output/max_velocity', - '/planning/scenario_planning/max_velocity_candidates'), - ('~/output/velocity_limit_clear_command', - '/planning/scenario_planning/clear_velocity_limit'), - ('~/output/trajectory', - '/planning/scenario_planning/lane_driving/trajectory'), - ('~/input/pointcloud', '/sensing/lidar/no_ground/pointcloud'), - ('~/input/objects', '/perception/object_recognition/objects'), - ('~/input/twist', '/localization/twist'), - ('~/input/trajectory', 'surround_obstacle_checker/trajectory'), + ("~/output/stop_reason", "/planning/scenario_planning/status/stop_reason"), + ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), + ("~/output/max_velocity", "/planning/scenario_planning/max_velocity_candidates"), + ( + "~/output/velocity_limit_clear_command", + "/planning/scenario_planning/clear_velocity_limit", + ), + ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), + ("~/input/pointcloud", "/sensing/lidar/no_ground/pointcloud"), + ("~/input/objects", "/perception/object_recognition/objects"), + ("~/input/twist", "/localization/twist"), + ("~/input/trajectory", "surround_obstacle_checker/trajectory"), ], parameters=[ common_param, obstacle_stop_planner_param, obstacle_stop_planner_acc_param, - {'enable_slow_down': False} - ], - extra_arguments=[ - {'use_intra_process_comms': LaunchConfiguration('use_intra_process')} + {"enable_slow_down": False}, ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) container = ComposableNodeContainer( - name='motion_planning_container', - namespace='', - package='rclcpp_components', - executable=LaunchConfiguration('container_executable'), + name="motion_planning_container", + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ obstacle_avoidance_planner_component, - obstacle_stop_planner_component + obstacle_stop_planner_component, ], ) surround_obstacle_checker_loader = LoadComposableNodes( composable_node_descriptions=[surround_obstacle_checker_component], target_container=container, - condition=IfCondition(LaunchConfiguration('use_surround_obstacle_check')), + condition=IfCondition(LaunchConfiguration("use_surround_obstacle_check")), ) relay_loader = LoadComposableNodes( composable_node_descriptions=[relay_component], target_container=container, - condition=UnlessCondition(LaunchConfiguration('use_surround_obstacle_check')), + condition=UnlessCondition(LaunchConfiguration("use_surround_obstacle_check")), ) set_container_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container', - condition=UnlessCondition(LaunchConfiguration('use_multithread')), + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), ) set_container_mt_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container_mt', - condition=IfCondition(LaunchConfiguration('use_multithread')), + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), ) - return launch.LaunchDescription([ - DeclareLaunchArgument( - 'input_path_topic', - default_value='/planning/scenario_planning/lane_driving/behavior_planning/path'), - DeclareLaunchArgument( - 'use_surround_obstacle_check', - default_value='true' - ), - DeclareLaunchArgument( - 'use_intra_process', - default_value='false' - ), - DeclareLaunchArgument( - 'use_multithread', - default_value='false' - ), - set_container_executable, - set_container_mt_executable, - container, - surround_obstacle_checker_loader, - relay_loader, - ]) + return launch.LaunchDescription( + [ + DeclareLaunchArgument( + "input_path_topic", + default_value="/planning/scenario_planning/lane_driving/behavior_planning/path", + ), + DeclareLaunchArgument("use_surround_obstacle_check", default_value="true"), + DeclareLaunchArgument("use_intra_process", default_value="false"), + DeclareLaunchArgument("use_multithread", default_value="false"), + set_container_executable, + set_container_mt_executable, + container, + surround_obstacle_checker_loader, + relay_loader, + ] + ) diff --git a/planning_launch/launch/scenario_planning/parking.launch.py b/planning_launch/launch/scenario_planning/parking.launch.py index b9ccd6cfc7..45e4331d00 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.py +++ b/planning_launch/launch/scenario_planning/parking.launch.py @@ -30,103 +30,105 @@ def generate_launch_description(): freespace_planner_param_path = os.path.join( - get_package_share_directory('planning_launch'), - 'config', - 'scenario_planning', - 'parking', - 'freespace_planner', - 'freespace_planner.param.yaml', + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "parking", + "freespace_planner", + "freespace_planner.param.yaml", ) - with open(freespace_planner_param_path, 'r') as f: - freespace_planner_param = yaml.safe_load(f)['/**']['ros__parameters'] + with open(freespace_planner_param_path, "r") as f: + freespace_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] container = ComposableNodeContainer( - name='parking_container', - namespace='', - package='rclcpp_components', - executable=LaunchConfiguration('container_executable'), + name="parking_container", + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ ComposableNode( - package='costmap_generator', - plugin='CostmapGenerator', - name='costmap_generator', + package="costmap_generator", + plugin="CostmapGenerator", + name="costmap_generator", remappings=[ - ('~/input/objects', '/perception/object_recognition/objects'), - ('~/input/points_no_ground', '/sensing/lidar/no_ground/pointcloud'), - ('~/input/vector_map', '/map/vector_map'), - ('~/input/scenario', '/planning/scenario_planning/scenario'), - ('~/output/grid_map', 'costmap_generator/grid_map'), - ('~/output/occupancy_grid', 'costmap_generator/occupancy_grid'), + ("~/input/objects", "/perception/object_recognition/objects"), + ("~/input/points_no_ground", "/sensing/lidar/no_ground/pointcloud"), + ("~/input/vector_map", "/map/vector_map"), + ("~/input/scenario", "/planning/scenario_planning/scenario"), + ("~/output/grid_map", "costmap_generator/grid_map"), + ("~/output/occupancy_grid", "costmap_generator/occupancy_grid"), ], parameters=[ { - 'costmap_frame': 'map', - 'vehicle_frame': 'base_link', - 'map_frame': 'map', - 'update_rate': 10.0, - 'use_wayarea': True, - 'use_objects': True, - 'use_points': True, - 'grid_min_value': 0.0, - 'grid_max_value': 1.0, - 'grid_resolution': 0.2, - 'grid_length_x': 70.0, - 'grid_length_y': 70.0, - 'grid_position_x': 0.0, - 'grid_position_y': 0.0, - 'maximum_lidar_height_thres': 0.3, - 'minimum_lidar_height_thres': -2.2, - 'expand_polygon_size': 1.0, - 'size_of_expansion_kernel': 9, + "costmap_frame": "map", + "vehicle_frame": "base_link", + "map_frame": "map", + "update_rate": 10.0, + "use_wayarea": True, + "use_objects": True, + "use_points": True, + "grid_min_value": 0.0, + "grid_max_value": 1.0, + "grid_resolution": 0.2, + "grid_length_x": 70.0, + "grid_length_y": 70.0, + "grid_position_x": 0.0, + "grid_position_y": 0.0, + "maximum_lidar_height_thres": 0.3, + "minimum_lidar_height_thres": -2.2, + "expand_polygon_size": 1.0, + "size_of_expansion_kernel": 9, }, ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], ), ComposableNode( - package='freespace_planner', - plugin='freespace_planner::FreespacePlannerNode', - name='freespace_planner', + package="freespace_planner", + plugin="freespace_planner::FreespacePlannerNode", + name="freespace_planner", remappings=[ - ('~/input/route', '/planning/mission_planning/route'), - ('~/input/occupancy_grid', 'costmap_generator/occupancy_grid'), - ('~/input/scenario', '/planning/scenario_planning/scenario'), - ('~/input/twist', '/localization/twist'), - ('~/output/trajectory', - '/planning/scenario_planning/parking/trajectory'), - ('is_completed', '/planning/scenario_planning/parking/is_completed'), + ("~/input/route", "/planning/mission_planning/route"), + ("~/input/occupancy_grid", "costmap_generator/occupancy_grid"), + ("~/input/scenario", "/planning/scenario_planning/scenario"), + ("~/input/twist", "/localization/twist"), + ("~/output/trajectory", "/planning/scenario_planning/parking/trajectory"), + ("is_completed", "/planning/scenario_planning/parking/is_completed"), ], parameters=[ freespace_planner_param, ], - extra_arguments=[{ - 'use_intra_process_comms': LaunchConfiguration('use_intra_process') - }], - ) + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ), ], ) set_container_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container', - condition=UnlessCondition(LaunchConfiguration('use_multithread')), + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), ) set_container_mt_executable = SetLaunchConfiguration( - 'container_executable', - 'component_container_mt', - condition=IfCondition(LaunchConfiguration('use_multithread')), + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), ) - return launch.LaunchDescription([ - DeclareLaunchArgument('use_intra_process', default_value='false', - description='use ROS2 component container communication'), - DeclareLaunchArgument('use_multithread', default_value='false', - description='use multithread'), - set_container_executable, - set_container_mt_executable, - GroupAction([ - PushRosNamespace('parking'), - container - ]) - ]) + return launch.LaunchDescription( + [ + DeclareLaunchArgument( + "use_intra_process", + default_value="false", + description="use ROS2 component container communication", + ), + DeclareLaunchArgument( + "use_multithread", default_value="false", description="use multithread" + ), + set_container_executable, + set_container_mt_executable, + GroupAction([PushRosNamespace("parking"), container]), + ] + ) diff --git a/planning_launch/package.xml b/planning_launch/package.xml index 36f5ab20d9..82ab4dbebf 100644 --- a/planning_launch/package.xml +++ b/planning_launch/package.xml @@ -24,7 +24,7 @@ turn_signal_decider ament_lint_auto - ament_lint_common + autoware_lint_common ament_cmake diff --git a/sensing_launch/package.xml b/sensing_launch/package.xml index f5b0339aeb..b5012e35ed 100644 --- a/sensing_launch/package.xml +++ b/sensing_launch/package.xml @@ -11,7 +11,7 @@ ament_cmake_auto ament_lint_auto - ament_lint_common + autoware_lint_common ament_cmake diff --git a/setup.cfg b/setup.cfg new file mode 100644 index 0000000000..fd61ed536e --- /dev/null +++ b/setup.cfg @@ -0,0 +1,15 @@ +[flake8] +# Modified from https://github.com/ament/ament_lint/blob/ebd524bb9973d5ec1dc48a670ce54f958a5a0243/ament_flake8/ament_flake8/configuration/ament_flake8.ini +extend-ignore = B902,C816,D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404,I202,CNL100,E203,E501,Q000 +import-order-style = google +max-line-length = 100 +show-source = true +statistics = true + +[isort] +profile=black +line_length=100 +force_sort_within_sections=true +force_single_line=true +reverse_relative=true +known_third_party=launch diff --git a/simulator_launch/package.xml b/simulator_launch/package.xml index 324c411cd8..03d415a7a8 100644 --- a/simulator_launch/package.xml +++ b/simulator_launch/package.xml @@ -15,7 +15,7 @@ simple_planning_simulator ament_lint_auto - ament_lint_common + autoware_lint_common ament_cmake diff --git a/system_launch/package.xml b/system_launch/package.xml index 0d79fe7416..b2150348ef 100644 --- a/system_launch/package.xml +++ b/system_launch/package.xml @@ -16,7 +16,7 @@ system_monitor ament_lint_auto - ament_lint_common + autoware_lint_common ament_cmake diff --git a/vehicle_launch/package.xml b/vehicle_launch/package.xml index a0dd136024..cec71a23c4 100644 --- a/vehicle_launch/package.xml +++ b/vehicle_launch/package.xml @@ -18,7 +18,7 @@ xacro ament_lint_auto - ament_lint_common + autoware_lint_common ament_cmake From b2dca3c3054fa1522e7c9cf72ec97f3b19f4e093 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 10 Nov 2021 13:59:22 +0900 Subject: [PATCH 307/851] twist -> odometry (#109) Co-authored-by: Takayuki Murooka --- control_launch/launch/control.launch.py | 8 ++++---- .../behavior_planning/behavior_planning.launch.py | 4 ++-- .../behavior_planning/behavior_planning.launch.xml | 2 +- .../motion_planning/motion_planning.launch.py | 4 ++-- .../launch/scenario_planning/parking.launch.py | 2 +- .../launch/scenario_planning/parking.launch.xml | 2 +- .../launch/scenario_planning/scenario_planning.launch.xml | 2 +- 7 files changed, 12 insertions(+), 12 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 4dd0408409..df8646e6c2 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -61,7 +61,7 @@ def launch_setup(context, *args, **kwargs): namespace="trajectory_follower", remappings=[ ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), - ("~/input/current_velocity", "/localization/twist"), + ("~/input/current_velocity", "/localization/kinematic_state"), ("~/input/current_steering", "/vehicle/status/steering"), ("~/output/control_raw", "lateral/control_cmd"), ("~/output/predicted_trajectory", "predicted_trajectory"), @@ -79,7 +79,7 @@ def launch_setup(context, *args, **kwargs): namespace="trajectory_follower", remappings=[ ("input/reference_trajectory", "/planning/scenario_planning/trajectory"), - ("input/current_velocity", "/localization/twist"), + ("input/current_velocity", "/localization/kinematic_state"), ("output/control_raw", "lateral/control_cmd"), ], parameters=[ @@ -95,7 +95,7 @@ def launch_setup(context, *args, **kwargs): name="velocity_controller", namespace="trajectory_follower", remappings=[ - ("~/current_velocity", "/localization/twist"), + ("~/current_velocity", "/localization/kinematic_state"), ("~/control_cmd", "longitudinal/control_cmd"), ("~/current_trajectory", "/planning/scenario_planning/trajectory"), ], @@ -132,7 +132,7 @@ def launch_setup(context, *args, **kwargs): name="lane_departure_checker_node", namespace="trajectory_follower", remappings=[ - ("~/input/twist", "/localization/twist"), + ("~/input/odometry", "/localization/kinematic_state"), ("~/input/lanelet_map_bin", "/map/vector_map"), ("~/input/route", "/planning/mission_planning/route"), ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index da2d221ad7..db7650b64b 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -129,7 +129,7 @@ def generate_launch_description(): ("~/input/route", LaunchConfiguration("input_route_topic_name")), ("~/input/vector_map", LaunchConfiguration("map_topic_name")), ("~/input/perception", "/perception/object_recognition/objects"), - ("~/input/velocity", "/localization/twist"), + ("~/input/odometry", "/localization/kinematic_state"), ( "~/input/external_approval", "/planning/scenario_planning/lane_driving/behavior_planning/" @@ -250,7 +250,7 @@ def generate_launch_description(): remappings=[ ("~/input/path_with_lane_id", "path_with_lane_id"), ("~/input/vector_map", "/map/vector_map"), - ("~/input/vehicle_velocity", "/localization/twist"), + ("~/input/odometry", "/localization/kinematic_state"), ("~/input/dynamic_objects", "/perception/object_recognition/objects"), ("~/input/no_ground_pointcloud", "/sensing/lidar/no_ground/pointcloud"), ( 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 d0c04d1320..4ec172ea35 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 @@ -9,7 +9,7 @@ - + diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index 79a0c31a94..4c06a7b8c0 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -92,7 +92,7 @@ def generate_launch_description(): ("~/output/trajectory", "surround_obstacle_checker/trajectory"), ("~/input/pointcloud", "/sensing/lidar/no_ground/pointcloud"), ("~/input/objects", "/perception/object_recognition/objects"), - ("~/input/twist", "/localization/twist"), + ("~/input/odometry", "/localization/kinematic_state"), ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), ], parameters=[ @@ -156,7 +156,7 @@ def generate_launch_description(): ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), ("~/input/pointcloud", "/sensing/lidar/no_ground/pointcloud"), ("~/input/objects", "/perception/object_recognition/objects"), - ("~/input/twist", "/localization/twist"), + ("~/input/odometry", "/localization/kinematic_state"), ("~/input/trajectory", "surround_obstacle_checker/trajectory"), ], parameters=[ diff --git a/planning_launch/launch/scenario_planning/parking.launch.py b/planning_launch/launch/scenario_planning/parking.launch.py index 45e4331d00..fef7775518 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.py +++ b/planning_launch/launch/scenario_planning/parking.launch.py @@ -92,7 +92,7 @@ def generate_launch_description(): ("~/input/route", "/planning/mission_planning/route"), ("~/input/occupancy_grid", "costmap_generator/occupancy_grid"), ("~/input/scenario", "/planning/scenario_planning/scenario"), - ("~/input/twist", "/localization/twist"), + ("~/input/odometry", "/localization/kinematic_state"), ("~/output/trajectory", "/planning/scenario_planning/parking/trajectory"), ("is_completed", "/planning/scenario_planning/parking/is_completed"), ], diff --git a/planning_launch/launch/scenario_planning/parking.launch.xml b/planning_launch/launch/scenario_planning/parking.launch.xml index f8254c8fa5..2465dac51f 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.xml +++ b/planning_launch/launch/scenario_planning/parking.launch.xml @@ -15,7 +15,7 @@ - + diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 808cff0110..82ec229d0d 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -8,7 +8,7 @@ - + From 0beb6f883399380249202a2187521228605d8117 Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Mon, 15 Nov 2021 15:11:04 +0900 Subject: [PATCH 308/851] Auto/fix launch (#110) * fix namespace * remove dynamic_object_visualization * fix rviz --- autoware_launch/rviz/autoware.rviz | 135 ++++++++++++++---- .../detection/detection.launch.xml | 7 - .../lidar_based_detection.launch.xml | 14 -- .../prediction/prediction.launch.xml | 7 - .../tracking/tracking.launch.xml | 6 - .../behavior_planning.launch.py | 2 +- simulator_launch/launch/simulator.launch.xml | 2 +- 7 files changed, 110 insertions(+), 63 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 99a2202f4d..ae020d33f5 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -718,64 +718,145 @@ Visualization Manager: Displays: - Class: rviz_common/Group Displays: - - Class: rviz_default_plugins/MarkerArray + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true Enabled: true - Name: DynamicObjects + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: DetectedObjects Namespaces: - label: true - path: false - path confidence: true - position covariance: true - shape: true - twist: true + {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/object_recognition/detection/objects/visualization + Value: /perception/object_recognition/detection/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 Value: true Enabled: false Name: Detection - Class: rviz_common/Group Displays: - - Class: rviz_default_plugins/MarkerArray + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/TrackedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true Enabled: true - Name: DynamicObjects + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: TrackedObjects Namespaces: - label: true - path: false - path confidence: true - position covariance: true - shape: true - twist: true + {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/object_recognition/tracking/objects/visualization + Value: /perception/object_recognition/tracking/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 Value: true Enabled: false Name: Tracking - Class: rviz_common/Group Displays: - - Class: rviz_default_plugins/MarkerArray + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/PredictedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true Enabled: true - Name: DynamicObjects + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: PredictedObjects Namespaces: - label: true - path: true - path confidence: true - position covariance: false - shape: true - twist: true + {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/object_recognition/objects/visualization + Value: /perception/object_recognition/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 Value: true Enabled: true Name: Prediction diff --git a/perception_launch/launch/object_recognition/detection/detection.launch.xml b/perception_launch/launch/object_recognition/detection/detection.launch.xml index 2a434005b4..55006f9fa1 100644 --- a/perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -57,11 +57,4 @@ - - - - - - - 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 2017a4de1f..e68632e1f7 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 @@ -24,13 +24,6 @@ - - - - - - - @@ -43,13 +36,6 @@ - - - - - - - diff --git a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml index 99f0b1e0cb..bd322ff679 100644 --- a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml +++ b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml @@ -13,11 +13,4 @@ - - - - - - - diff --git a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml index e34a5bc54d..64bcad42fa 100644 --- a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml +++ b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml @@ -4,10 +4,4 @@ - - - - - - diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index db7650b64b..3fdef123b2 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -250,7 +250,7 @@ def generate_launch_description(): remappings=[ ("~/input/path_with_lane_id", "path_with_lane_id"), ("~/input/vector_map", "/map/vector_map"), - ("~/input/odometry", "/localization/kinematic_state"), + ("~/input/vehicle_odometry", "/localization/kinematic_state"), ("~/input/dynamic_objects", "/perception/object_recognition/objects"), ("~/input/no_ground_pointcloud", "/sensing/lidar/no_ground/pointcloud"), ( diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index 0253d8d094..82a9ec8d5d 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -28,7 +28,7 @@ - + From 07555e19d3bf42a245c3eb5c58e2f1b84e43a475 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Mon, 15 Nov 2021 16:53:15 +0900 Subject: [PATCH 309/851] Update package.xml (#111) --- perception_launch/package.xml | 2 -- 1 file changed, 2 deletions(-) diff --git a/perception_launch/package.xml b/perception_launch/package.xml index d54c251440..865d3c4b71 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -10,13 +10,11 @@ ament_cmake_auto - dynamic_object_visualization euclidean_cluster image_transport_decompressor lidar_apollo_instance_segmentation map_based_prediction multi_object_tracker - naive_path_prediction object_merger object_range_splitter roi_cluster_fusion From bbd4290f34dc653bf9e29e79e04ae84156c2aa58 Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Mon, 15 Nov 2021 18:37:39 +0900 Subject: [PATCH 310/851] remove unused depend/launcher (#112) --- control_launch/package.xml | 5 +---- .../detection/lidar_based_detection.launch.xml | 9 --------- planning_launch/package.xml | 2 -- 3 files changed, 1 insertion(+), 15 deletions(-) diff --git a/control_launch/package.xml b/control_launch/package.xml index a6ad01d375..599b3d14b3 100644 --- a/control_launch/package.xml +++ b/control_launch/package.xml @@ -13,12 +13,9 @@ external_cmd_converter lane_departure_checker - latlon_muxer - mpc_follower - pure_pursuit shift_decider + trajectory_follower_nodes vehicle_cmd_gate - velocity_controller ament_lint_auto autoware_lint_common 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 e68632e1f7..1c24b475cf 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 @@ -46,13 +46,4 @@ - - - - - - - - - diff --git a/planning_launch/package.xml b/planning_launch/package.xml index 82ab4dbebf..ccb151e6cb 100644 --- a/planning_launch/package.xml +++ b/planning_launch/package.xml @@ -14,14 +14,12 @@ costmap_generator external_velocity_limit_selector freespace_planner - lane_change_planner mission_planner motion_velocity_smoother obstacle_avoidance_planner obstacle_stop_planner scenario_selector surround_obstacle_checker - turn_signal_decider ament_lint_auto autoware_lint_common From fad8288f0d33feb849ca3556e3c042ffdf1d44ef Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Tue, 16 Nov 2021 12:49:39 +0900 Subject: [PATCH 311/851] Auto/control psim (#113) * succeeded in launching control nodes * fix input/output of control_launch * Remove multiple package * Add newline * Update control_launch/launch/control.launch.py Co-authored-by: tkimura4 * Apply pre-commit Co-authored-by: Takayuki Murooka Co-authored-by: tkimura4 --- .../lateral_controller.param.yaml | 72 +++++++++ .../latlon_muxer.param.yaml | 3 + .../longitudinal_controller.param.yaml | 82 ++++++++++ control_launch/launch/control.launch.py | 140 ++++++++---------- control_launch/launch/control.launch.xml | 33 ++--- control_launch/package.xml | 1 + 6 files changed, 237 insertions(+), 94 deletions(-) create mode 100644 control_launch/config/trajectory_follower/lateral_controller.param.yaml create mode 100644 control_launch/config/trajectory_follower/latlon_muxer.param.yaml create mode 100644 control_launch/config/trajectory_follower/longitudinal_controller.param.yaml diff --git a/control_launch/config/trajectory_follower/lateral_controller.param.yaml b/control_launch/config/trajectory_follower/lateral_controller.param.yaml new file mode 100644 index 0000000000..50c6c5cc0b --- /dev/null +++ b/control_launch/config/trajectory_follower/lateral_controller.param.yaml @@ -0,0 +1,72 @@ +/**: + 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 + use_steer_prediction: false # flag for using steer prediction (do not use steer measurement) + admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value + admissible_yaw_error_rad: 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 -- + qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or 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_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.0 # threshold of curvature to use "low_curvature" parameter (recommend: 0.01~0.03) + 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 + mpc_acceleration_limit: 2.0 # limit on the vehicle's acceleration + mpc_velocity_time_constant: 0.3 # time constant used for velocity smoothing + + # -- 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.1 # steering dynamics time constant (1d approximation) [s] + steer_lim_deg: 20.0 # steering angle limit [deg] + 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] + error_deriv_lpf_cutoff_hz: 5.0 + + # stop state + stop_state_entry_ego_speed: 0.2 + stop_state_entry_target_speed: 0.5 + stop_state_keep_stopping_dist: 0.5 + + # vehicle parameters + vehicle: + cg_to_front_m: 1.228 + cg_to_rear_m: 1.5618 + mass_kg: 2400.0 + mass_fl: 600.0 + mass_fr: 600.0 + mass_rl: 600.0 + mass_rr: 600.0 + cf: 155494.663 + cr: 155494.663 diff --git a/control_launch/config/trajectory_follower/latlon_muxer.param.yaml b/control_launch/config/trajectory_follower/latlon_muxer.param.yaml new file mode 100644 index 0000000000..371bb99787 --- /dev/null +++ b/control_launch/config/trajectory_follower/latlon_muxer.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + timeout_thr_sec: 0.5 # [s] Time limit after which input messages are discarded. diff --git a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml new file mode 100644 index 0000000000..3f833342ad --- /dev/null +++ b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml @@ -0,0 +1,82 @@ +/**: + ros__parameters: + control_rate: 30.0 + delay_compensation_time: 0.17 + + enable_smooth_stop: true + enable_overshoot_emergency: true + enable_slope_compensation: false + + # state transition + drive_state_stop_dist: 0.5 + drive_state_offset_stop_dist: 1.0 + stopping_state_stop_dist: 0.49 + stopped_state_entry_vel: 0.1 + stopped_state_entry_acc: 0.1 + emergency_state_overshoot_stop_dist: 1.5 + emergency_state_traj_trans_dev: 3.0 + emergency_state_traj_rot_dev: 0.7 + + # drive state + kp: 1.0 + ki: 0.1 + 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.0 + min_d_effort: 0.0 + lpf_vel_error_gain: 0.9 + current_vel_threshold_pid_integration: 0.5 + + # smooth stop state + smooth_stop_max_strong_acc: -0.5 + smooth_stop_min_strong_acc: -1.0 + smooth_stop_weak_acc: -0.3 + smooth_stop_weak_stop_acc: -0.8 + smooth_stop_strong_stop_acc: -3.4 + smooth_stop_max_fast_vel: 0.5 + smooth_stop_min_running_vel: 0.01 + smooth_stop_min_running_acc: 0.01 + smooth_stop_weak_stop_time: 0.8 + smooth_stop_weak_stop_dist: -0.3 + smooth_stop_strong_stop_dist: -0.5 + + # stopped state + stopped_vel: 0.0 + stopped_acc: -3.4 + stopped_jerk: -5.0 + + # emergency state + emergency_vel: 0.0 + emergency_acc: -5.0 + emergency_jerk: -3.0 + + # acceleration limit + max_acc: 3.0 + min_acc: -5.0 + + # jerk limit + max_jerk: 2.0 + min_jerk: -5.0 + + # pitch + use_trajectory_for_pitch_calculation: false + lpf_pitch_gain: 0.95 + max_pitch_rad: 0.1 + min_pitch_rad: -0.1 + + # vehicle parameters + vehicle: + cg_to_front_m: 1.228 + cg_to_rear_m: 1.5618 + mass_kg: 2400.0 + mass_fl: 600.0 + mass_fr: 600.0 + mass_rl: 600.0 + mass_rr: 600.0 + cf: 155494.663 + cr: 155494.663 diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index df8646e6c2..f11a7b3f8e 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -19,7 +19,6 @@ from launch.actions import OpaqueFunction from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition -from launch.conditions import LaunchConfigurationEquals from launch.conditions import UnlessCondition from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration @@ -32,17 +31,16 @@ def launch_setup(context, *args, **kwargs): - mpc_follower_param_path = LaunchConfiguration("mpc_follower_param_path").perform(context) - with open(mpc_follower_param_path, "r") as f: - mpc_follower_param = yaml.safe_load(f)["/**"]["ros__parameters"] - pure_pursuit_param_path = LaunchConfiguration("pure_pursuit_param_path").perform(context) - with open(pure_pursuit_param_path, "r") as f: - pure_pursuit_param = yaml.safe_load(f)["/**"]["ros__parameters"] - velocity_controller_param_path = LaunchConfiguration("velocity_controller_param_path").perform( - context - ) - with open(velocity_controller_param_path, "r") as f: - velocity_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] + lat_controller_param_path = LaunchConfiguration("lat_controller_param_path").perform(context) + with open(lat_controller_param_path, "r") as f: + lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] + lon_controller_param_path = LaunchConfiguration("lon_controller_param_path").perform(context) + with open(lon_controller_param_path, "r") as f: + lon_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] + latlon_muxer_param_path = LaunchConfiguration("latlon_muxer_param_path").perform(context) + with open(latlon_muxer_param_path, "r") as f: + latlon_muxer_param = yaml.safe_load(f)["/**"]["ros__parameters"] + vehicle_cmd_gate_param_path = LaunchConfiguration("vehicle_cmd_gate_param_path").perform( context ) @@ -53,54 +51,42 @@ def launch_setup(context, *args, **kwargs): ).perform(context) with open(lane_departure_checker_param_path, "r") as f: lane_departure_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] - # mpc follower - mpc_follower_component = ComposableNode( - package="mpc_follower", - plugin="MPCFollower", - name="mpc_follower", + + # lateral controller + lat_controller_component = ComposableNode( + package="trajectory_follower_nodes", + plugin="autoware::motion::control::trajectory_follower_nodes::LateralController", + name="lateral_controller_node_exe", namespace="trajectory_follower", remappings=[ ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), - ("~/input/current_velocity", "/localization/kinematic_state"), + ("~/input/current_odometry", "/localization/kinematic_state"), ("~/input/current_steering", "/vehicle/status/steering"), - ("~/output/control_raw", "lateral/control_cmd"), - ("~/output/predicted_trajectory", "predicted_trajectory"), + ("~/output/control_cmd", "lateral/control_cmd"), + ("~/output/predicted_trajectory", "lateral/predicted_trajectory"), + ("~/output/diagnostic", "lateral/diagnostic"), ], parameters=[ - mpc_follower_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - # pure pursuit - pure_pursuit_component = ComposableNode( - package="pure_pursuit", - plugin="PurePursuitNode", - name="pure_pursuit", - namespace="trajectory_follower", - remappings=[ - ("input/reference_trajectory", "/planning/scenario_planning/trajectory"), - ("input/current_velocity", "/localization/kinematic_state"), - ("output/control_raw", "lateral/control_cmd"), - ], - parameters=[ - pure_pursuit_param, + lat_controller_param, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - # velocity controller - velocity_controller_component = ComposableNode( - package="velocity_controller", - plugin="VelocityController", - name="velocity_controller", + # longitudinal controller + lon_controller_component = ComposableNode( + package="trajectory_follower_nodes", + plugin="autoware::motion::control::trajectory_follower_nodes::LongitudinalController", + name="longitudinal_controller_node_exe", namespace="trajectory_follower", remappings=[ - ("~/current_velocity", "/localization/kinematic_state"), - ("~/control_cmd", "longitudinal/control_cmd"), - ("~/current_trajectory", "/planning/scenario_planning/trajectory"), + ("~/input/current_trajectory", "/planning/scenario_planning/trajectory"), + ("~/input/current_odometry", "/localization/kinematic_state"), + ("~/output/control_cmd", "longitudinal/control_cmd"), + ("~/output/slope_angle", "longitudinal/slope_angle"), + ("~/output/diagnostic", "longitudinal/diagnostic"), ], parameters=[ - velocity_controller_param, + lon_controller_param, { "control_rate": LaunchConfiguration("control_rate"), "show_debug_info": LaunchConfiguration("show_debug_info"), @@ -113,15 +99,18 @@ def launch_setup(context, *args, **kwargs): # latlon muxer latlon_muxer_component = ComposableNode( - package="latlon_muxer", - plugin="LatLonMuxer", - name="latlon_muxer", + package="trajectory_follower_nodes", + plugin="autoware::motion::control::trajectory_follower_nodes::LatLonMuxer", + name="latlon_muxer_node_exe", namespace="trajectory_follower", remappings=[ ("input/lateral/control_cmd", "lateral/control_cmd"), ("input/longitudinal/control_cmd", "longitudinal/control_cmd"), ("output/control_cmd", "control_cmd"), ], + parameters=[ + latlon_muxer_param, + ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) @@ -229,7 +218,7 @@ def launch_setup(context, *args, **kwargs): package="rclcpp_components", executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ - velocity_controller_component, + lon_controller_component, latlon_muxer_component, lane_departure_component, shift_decider_component, @@ -237,16 +226,11 @@ def launch_setup(context, *args, **kwargs): ], ) - mpc_follower_loader = LoadComposableNodes( - composable_node_descriptions=[mpc_follower_component], - target_container=container, - condition=LaunchConfigurationEquals("lateral_controller_mode", "mpc_follower"), - ) - - pure_pursuit_loader = LoadComposableNodes( - composable_node_descriptions=[pure_pursuit_component], + # lateral controller is separated since it may be another controller (e.g. pure pursuit) + lat_controller_loader = LoadComposableNodes( + composable_node_descriptions=[lat_controller_component], target_container=container, - condition=LaunchConfigurationEquals("lateral_controller_mode", "pure_pursuit"), + # condition=LaunchConfigurationEquals("lateral_controller_mode", "mpc"), ) group = GroupAction( @@ -255,8 +239,7 @@ def launch_setup(context, *args, **kwargs): container, external_cmd_selector_loader, external_cmd_converter_loader, - mpc_follower_loader, - pure_pursuit_loader, + lat_controller_loader, ] ) @@ -271,28 +254,35 @@ def add_launch_arg(name: str, default_value=None, description=None): DeclareLaunchArgument(name, default_value=default_value, description=description) ) + # add_launch_arg( + # "lateral_controller_mode", + # "mpc_follower", + # "lateral controller mode: `mpc_follower` or `pure_pursuit`", + # ) + add_launch_arg( - "lateral_controller_mode", - "mpc_follower", - "lateral controller mode: `mpc_follower` or `pure_pursuit`", - ) - add_launch_arg( - "mpc_follower_param_path", - [FindPackageShare("control_launch"), "/config/mpc_follower/mpc_follower.param.yaml"], - "path to the parameter file of mpc_follower", + "lat_controller_param_path", + [ + FindPackageShare("control_launch"), + "/config/trajectory_follower/lateral_controller.param.yaml", + ], + "path to the parameter file of lateral controller", ) add_launch_arg( - "pure_pursuit_param_path", - [FindPackageShare("control_launch"), "/config/pure_pursuit/pure_pursuit.param.yaml"], - "path to the parameter file of pure_pursuit", + "lon_controller_param_path", + [ + FindPackageShare("control_launch"), + "/config/trajectory_follower/longitudinal_controller.param.yaml", + ], + "path to the parameter file of longitudinal controller", ) add_launch_arg( - "velocity_controller_param_path", + "latlon_muxer_param_path", [ FindPackageShare("control_launch"), - "/config/velocity_controller/velocity_controller.param.yaml", + "/config/trajectory_follower/latlon_muxer.param.yaml", ], - "path to the parameter file of velocity controller", + "path to the parameter file of latlon muxer", ) add_launch_arg( "vehicle_cmd_gate_param_path", diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index b8115d42a0..9cf2f91a42 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -1,12 +1,12 @@ - + - - - + + + @@ -18,29 +18,24 @@ - - - - - - - - - - - + + + + + - - + + - + + - + diff --git a/control_launch/package.xml b/control_launch/package.xml index 599b3d14b3..ed1180a06e 100644 --- a/control_launch/package.xml +++ b/control_launch/package.xml @@ -14,6 +14,7 @@ external_cmd_converter lane_departure_checker shift_decider + trajectory_follower trajectory_follower_nodes vehicle_cmd_gate From c9486c90895458bc366860c612a52f6c3f65c598 Mon Sep 17 00:00:00 2001 From: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Date: Wed, 17 Nov 2021 11:07:55 +0900 Subject: [PATCH 312/851] change topic name for rviz plugin (#114) --- autoware_launch/rviz/autoware.rviz | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index ae020d33f5..e39b384bf4 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -79,7 +79,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /vehicle/status/steering + Value: /vehicle/status/steering_status Value: true Value height offset: 0 - Class: rviz_plugins/ConsoleMeter @@ -95,7 +95,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /vehicle/status/twist + Value: /vehicle/status/velocity_status Value: true Value height offset: 0 - Alpha: 0.999 @@ -113,7 +113,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /vehicle/status/twist + Value: /vehicle/status/velocity_status Value: true - Alpha: 0.30000001192092896 Class: rviz_default_plugins/RobotModel From 2610a6bfb3575e348188319df61f87b2ccfe14fc Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Wed, 17 Nov 2021 12:51:18 +0900 Subject: [PATCH 313/851] Fix remapping in control.launch.py (#115) * Fix remappings * Add comment --- control_launch/launch/control.launch.py | 39 +++++++++++-------- .../behavior_planning.launch.py | 3 +- .../behavior_planning.launch.xml | 3 +- 3 files changed, 26 insertions(+), 19 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index f11a7b3f8e..dbd4da69eb 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -61,7 +61,7 @@ def launch_setup(context, *args, **kwargs): remappings=[ ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), ("~/input/current_odometry", "/localization/kinematic_state"), - ("~/input/current_steering", "/vehicle/status/steering"), + ("~/input/current_steering", "/vehicle/status/steering_status"), ("~/output/control_cmd", "lateral/control_cmd"), ("~/output/predicted_trajectory", "lateral/predicted_trajectory"), ("~/output/diagnostic", "lateral/diagnostic"), @@ -104,9 +104,9 @@ def launch_setup(context, *args, **kwargs): name="latlon_muxer_node_exe", namespace="trajectory_follower", remappings=[ - ("input/lateral/control_cmd", "lateral/control_cmd"), - ("input/longitudinal/control_cmd", "longitudinal/control_cmd"), - ("output/control_cmd", "control_cmd"), + ("~/input/lateral/control_cmd", "lateral/control_cmd"), + ("~/input/longitudinal/control_cmd", "longitudinal/control_cmd"), + ("~/output/control_cmd", "control_cmd"), ], parameters=[ latlon_muxer_param, @@ -125,8 +125,10 @@ def launch_setup(context, *args, **kwargs): ("~/input/lanelet_map_bin", "/map/vector_map"), ("~/input/route", "/planning/mission_planning/route"), ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), - ("~/input/predicted_trajectory", "/control/trajectory_follower/predicted_trajectory"), - ("~/input/covariance", "/localization/pose_with_covariance"), + ( + "~/input/predicted_trajectory", + "/control/trajectory_follower/lateral/predicted_trajectory", + ), ], parameters=[lane_departure_checker_param], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], @@ -139,7 +141,7 @@ def launch_setup(context, *args, **kwargs): name="shift_decider", remappings=[ ("input/control_cmd", "/control/trajectory_follower/control_cmd"), - ("output/shift_cmd", "/control/shift_decider/shift_cmd"), + ("output/gear_cmd", "/control/shift_decider/gear_cmd"), ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) @@ -151,22 +153,25 @@ def launch_setup(context, *args, **kwargs): name="vehicle_cmd_gate", remappings=[ ("input/emergency_state", "/system/emergency/emergency_state"), - ("input/steering", "/vehicle/status/steering"), - ("input/auto/control_cmd", "trajectory_follower/control_cmd"), - ("input/auto/turn_signal_cmd", "/planning/turn_signal_decider/turn_signal_cmd"), - ("input/auto/shift_cmd", "/control/shift_decider/shift_cmd"), + ("input/steering", "/vehicle/status/steering_status"), + ("input/auto/control_cmd", "/control/trajectory_follower/control_cmd"), + ("input/auto/turn_indicators_cmd", "/planning/turn_indicators_cmd"), + ("input/auto/hazard_lights_cmd", "/planning/hazard_lights_cmd"), + ("input/auto/gear_cmd", "/control/shift_decider/gear_cmd"), + # TODO(Fumiya Watanabe): fix remapping when external_cmd_selector and external_cmd_converter is ported ("input/external/control_cmd", "/external/selected/control_cmd"), ("input/external/turn_signal_cmd", "/external/selected/turn_signal_cmd"), ("input/external/shift_cmd", "/external/selected/shift_cmd"), ("input/external_emergency_stop_heartbeat", "/external/selected/heartbeat"), ("input/gate_mode", "/control/gate_mode_cmd"), ("input/emergency/control_cmd", "/system/emergency/control_cmd"), - ("input/emergency/turn_signal_cmd", "/system/emergency/turn_signal_cmd"), - ("input/emergency/shift_cmd", "/system/emergency/shift_cmd"), - ("output/vehicle_cmd", "vehicle_cmd"), - ("output/control_cmd", "/control/control_cmd"), - ("output/shift_cmd", "/control/shift_cmd"), - ("output/turn_signal_cmd", "/control/turn_signal_cmd"), + ("input/emergency/hazard_lights_cmd", "/system/emergency/hazard_lights_cmd"), + ("input/emergency/gear_cmd", "/system/emergency/gear_cmd"), + ("output/vehicle_cmd_emergency", "/control/command/emergency_cmd"), + ("output/control_cmd", "/control/command/control_cmd"), + ("output/gear_cmd", "/control/command/gear_cmd"), + ("output/turn_indicators_cmd", "/control/command/turn_indicators_cmd"), + ("output/hazard_lights_cmd", "/control/command/hazard_lights_cmd"), ("output/gate_mode", "/control/current_gate_mode"), ("output/engage", "/api/autoware/get/engage"), ("output/external_emergency", "/api/autoware/get/emergency"), diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 3fdef123b2..8f33bfcebb 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -156,7 +156,8 @@ def generate_launch_description(): "/planning/scenario_planning/lane_driving/behavior_planning/" "behavior_path_planner/force_available", ), - ("~/output/turn_signal_cmd", "/planning/turn_signal_decider/turn_signal_cmd"), + ("~/output/turn_indicators_cmd", "/planning/turn_indicators_cmd"), + ("~/output/hazard_lights_cmd", "/planning/hazard_lights_cmd"), ], parameters=[ side_shift_param, 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 4ec172ea35..2b9f7d91e7 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 @@ -16,7 +16,8 @@ - + + From fa125c924d91d756338e231f7394508f55cfc5e9 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Wed, 17 Nov 2021 18:08:36 +0900 Subject: [PATCH 314/851] Fix remappings (#116) * fix topics * add external hazard indicator --- control_launch/launch/control.launch.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index dbd4da69eb..d7487d8298 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -158,10 +158,10 @@ def launch_setup(context, *args, **kwargs): ("input/auto/turn_indicators_cmd", "/planning/turn_indicators_cmd"), ("input/auto/hazard_lights_cmd", "/planning/hazard_lights_cmd"), ("input/auto/gear_cmd", "/control/shift_decider/gear_cmd"), - # TODO(Fumiya Watanabe): fix remapping when external_cmd_selector and external_cmd_converter is ported ("input/external/control_cmd", "/external/selected/control_cmd"), - ("input/external/turn_signal_cmd", "/external/selected/turn_signal_cmd"), - ("input/external/shift_cmd", "/external/selected/shift_cmd"), + ("input/external/turn_indicators_cmd", "/external/selected/turn_indicators_cmd"), + ("input/external/hazard_lights_cmd", "/external/selected/hazard_lights_cmd"), + ("input/external/gear_cmd", "/external/selected/gear_cmd"), ("input/external_emergency_stop_heartbeat", "/external/selected/heartbeat"), ("input/gate_mode", "/control/gate_mode_cmd"), ("input/emergency/control_cmd", "/system/emergency/control_cmd"), From 6b889e6ca1483a94602d4ccccc4908a00a9d8140 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 18 Nov 2021 14:56:54 +0900 Subject: [PATCH 315/851] Fix diagnostic_aggregator config path (#118) --- system_launch/launch/system.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index af34ae61e5..8ae917f308 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -34,7 +34,7 @@ - + From 16b3c1e15ae23b864da36c03a818568ffdb77252 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 18 Nov 2021 18:02:00 +0900 Subject: [PATCH 316/851] Auto/launcher ground segmentation (#117) * add base line launch * add ground_segmentation launcher * run pre-commit * clean up * fix coding style * fix topic name * fix yaml params * fix loader name * rename components * improve implementation --- autoware_launch/launch/autoware.launch.xml | 2 + .../launch/logging_simulator.launch.xml | 2 + .../aip_x2_perception.param.yaml | 3 + .../aip_xx1_perception.param.yaml | 3 + .../ground_segmentation.launch.py | 280 ++++++++++++++++++ .../launch/perception.launch.xml | 18 ++ 6 files changed, 308 insertions(+) create mode 100644 perception_launch/config/object_segmentation/ground_segmentation/aip_x2_perception.param.yaml create mode 100644 perception_launch/config/object_segmentation/ground_segmentation/aip_xx1_perception.param.yaml create mode 100644 perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index cd969f1d6f..749881c937 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -48,6 +48,8 @@ + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index dbc45ed714..612258a334 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -74,6 +74,8 @@ + + diff --git a/perception_launch/config/object_segmentation/ground_segmentation/aip_x2_perception.param.yaml b/perception_launch/config/object_segmentation/ground_segmentation/aip_x2_perception.param.yaml new file mode 100644 index 0000000000..e327ec3f1c --- /dev/null +++ b/perception_launch/config/object_segmentation/ground_segmentation/aip_x2_perception.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + additional_lidars: ["front_upper", "front_lower"] diff --git a/perception_launch/config/object_segmentation/ground_segmentation/aip_xx1_perception.param.yaml b/perception_launch/config/object_segmentation/ground_segmentation/aip_xx1_perception.param.yaml new file mode 100644 index 0000000000..8723b3b263 --- /dev/null +++ b/perception_launch/config/object_segmentation/ground_segmentation/aip_xx1_perception.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + additional_lidars: [] diff --git a/perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py new file mode 100644 index 0000000000..cc3906fe09 --- /dev/null +++ b/perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -0,0 +1,280 @@ +# 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.actions import IncludeLaunchDescription +from launch.actions import OpaqueFunction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes +from launch_ros.descriptions import ComposableNode +from launch_ros.substitutions import FindPackageShare +import yaml + + +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 create_additional_pipeline(vehicle_info, lidar_name): + crop_box_filter_component = ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::CropBoxFilterComponent", + name=f"{lidar_name}_crop_box_filter", + remappings=[ + ("input", f"/sensing/lidar/{lidar_name}/outlier_filtered/pointcloud"), + ("output", f"{lidar_name}/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, + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + ground_filter_component = ComposableNode( + package="ground_segmentation", + plugin="ground_segmentation::ScanGroundFilterComponent", + name=f"{lidar_name}_scan_ground_filter", + remappings=[ + ("input", f"{lidar_name}/measurement_range_cropped/pointcloud"), + ("output", f"{lidar_name}/no_ground/pointcloud"), + ], + parameters=[ + { + "global_slope_max_angle_deg": 10.0, + "local_slope_max_angle_deg": 30.0, + "split_points_distance_tolerance": 0.1, + "split_height_distance": 0.05, + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + return [crop_box_filter_component, ground_filter_component] + + +def launch_setup(context, *args, **kwargs): + + vehicle_info = get_vehicle_info(context) + + path = LaunchConfiguration("perception_config_file").perform(context) + with open(path, "r") as f: + pipeline_param = yaml.safe_load(f)["/**"]["ros__parameters"] + + additional_pipeline_components = [] + for lidar_name in pipeline_param["additional_lidars"]: + additional_pipeline_components.extend(create_additional_pipeline(vehicle_info, lidar_name)) + + crop_box_filter_component = ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::CropBoxFilterComponent", + name="crop_box_filter", + remappings=[ + ("input", "/sensing/lidar/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, + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + ground_filter_component = ComposableNode( + package="ground_segmentation", + plugin="ground_segmentation::ScanGroundFilterComponent", + name="scan_ground_filter", + remappings=[ + ("input", "measurement_range_cropped/pointcloud"), + ("output", "no_ground/pointcloud"), + ], + parameters=[ + { + "global_slope_max_angle_deg": 10.0, + "local_slope_max_angle_deg": 30.0, + "split_points_distance_tolerance": 0.2, + "split_height_distance": 0.2, + "use_virtual_ground_point": False, + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + ground_concat_topics = ["no_ground/pointcloud"] + for lidar_name in pipeline_param["additional_lidars"]: + ground_concat_topics.extend([f"{lidar_name}/no_ground/pointcloud"]) + + concat_data_component = ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + name="concatenate_data", + remappings=[("output", "no_ground/oneshot/pointcloud")], + parameters=[ + { + "input_topics": ground_concat_topics, + "output_frame": LaunchConfiguration("base_frame"), + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + laserscan_to_occupancy_grid_map_loader = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + FindPackageShare("laserscan_to_occupancy_grid_map"), + "/launch/laserscan_to_occupancy_grid_map.launch.py", + ] + ), + launch_arguments={ + "container": "/perception/object_segmentation/ground_segmentation/perception_pipeline_container", + "input/obstacle_pointcloud": "no_ground/oneshot/pointcloud" + if bool(pipeline_param["additional_lidars"]) + else "no_ground/pointcloud", + "input/raw_pointcloud": "/sensing/lidar/concatenated/pointcloud", + "output": "occupancy_grid", + "use_intra_process": LaunchConfiguration("use_intra_process"), + }.items(), + ) + + occupancy_grid_map_outlier_component = ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::OccupancyGridMapOutlierFilterComponent", + name="occupancy_grid_map_outlier_filter", + remappings=[ + ("~/input/occupancy_grid_map", "occupancy_grid"), + ( + "~/input/pointcloud", + "no_ground/oneshot/pointcloud" + if bool(pipeline_param["additional_lidars"]) + else "no_ground/pointcloud", + ), + ("~/output/pointcloud", "/perception/object_segmentation/pointcloud"), + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name="perception_pipeline_container", + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=[ + crop_box_filter_component, + ground_filter_component, + occupancy_grid_map_outlier_component, + ], + output="screen", + ) + + additional_pipeline_loader = LoadComposableNodes( + composable_node_descriptions=additional_pipeline_components, + target_container=container, + condition=IfCondition( + LaunchConfiguration( + "use_additional_pipeline", default=bool(pipeline_param["additional_lidars"]) + ) + ), + ) + + concat_data_component_loader = LoadComposableNodes( + composable_node_descriptions=[concat_data_component], + target_container=container, + condition=IfCondition( + LaunchConfiguration( + "use_additional_pipeline", default=bool(pipeline_param["additional_lidars"]) + ) + ), + ) + + return [ + container, + additional_pipeline_loader, + concat_data_component_loader, + laserscan_to_occupancy_grid_map_loader, + ] + + +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("perception_config_file") + add_launch_arg("use_multithread", "False") + add_launch_arg("use_intra_process", "True") + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + + return launch.LaunchDescription( + launch_arguments + + [set_container_executable, set_container_mt_executable] + + [OpaqueFunction(function=launch_setup)] + ) diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 3cbb396bab..65bc16c8e0 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -1,6 +1,8 @@ + + @@ -27,6 +29,22 @@ + + + + + + + + + + + + + + + + From f540e3e472d03dac200296489c2d6e720c0cab85 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Thu, 18 Nov 2021 22:30:53 +0900 Subject: [PATCH 317/851] Sync .auto branch with the latest branch in internal repository (#120) * Disbale intersection polygon marker (#483) Signed-off-by: wep21 * Merge pull request #384 from tier4/feature/no_stopping_area Feature/no stopping area Signed-off-by: Kenji Miyake Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> --- autoware_launch/rviz/autoware.rviz | 21 +++++++++++++++++++ .../behavior_planning.launch.py | 10 +++++++++ 2 files changed, 31 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index e39b384bf4..3c2a198a03 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1022,6 +1022,8 @@ Visualization Manager: Enabled: true Name: Intersection Namespaces: + candidate_collision_ego_lane_polygon: false + candidate_collision_object_polygons: false conflicting_targets: false detection_area: false ego_lane: false @@ -1142,6 +1144,25 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/occlusion_spot Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: NoStoppingArea + Namespaces: + no_stopping_area_correspondence: false + no_stopping_area_id: false + no_stopping_area_polygon: false + stuck_vehicle_detect_area: false + stop_line_detect_area: false + stuck_points: false + stop_factor_text: true + stop_virtual_wall: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_stopping_area + Value: true - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 8f33bfcebb..88bb6b419a 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -243,6 +243,14 @@ def generate_launch_description(): with open(occlusion_spot_param_path, "r") as f: occlusion_spot_param = yaml.safe_load(f)["/**"]["ros__parameters"] + no_stopping_area_param_path = os.path.join( + get_package_share_directory("behavior_velocity_planner"), + "config", + "no_stopping_area.param.yaml", + ) + with open(no_stopping_area_param_path, "r") as f: + no_stopping_area_param = yaml.safe_load(f)["/**"]["ros__parameters"] + behavior_velocity_planner_component = ComposableNode( package="behavior_velocity_planner", plugin="behavior_velocity_planner::BehaviorVelocityPlannerNode", @@ -282,6 +290,7 @@ def generate_launch_description(): "launch_detection_area": True, "launch_virtual_traffic_light": True, "launch_occlusion_spot": True, + "launch_no_stopping_area": True, "forward_path_length": 1000.0, "backward_path_length": 5.0, "max_accel": -2.8, @@ -295,6 +304,7 @@ def generate_launch_description(): traffic_light_param, virtual_traffic_light_param, occlusion_spot_param, + no_stopping_area_param, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) From c40b09ce186e5c37cd0b9e6c8c6dc4ec44390f1e Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Fri, 19 Nov 2021 16:57:22 +0900 Subject: [PATCH 318/851] fix turn signal to indicators (#123) --- 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 3c2a198a03..916bde22cc 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -326,7 +326,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /control/turn_signal_cmd + Value: /vehicle/status/turn_indicators_status Value: true Width: 512 Enabled: true From 8a6c097c8a0c3220fdfcc9cb62267749b8613a74 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 19 Nov 2021 17:50:33 +0900 Subject: [PATCH 319/851] add feature remover (#122) --- .../camera_lidar_fusion_based_detection.launch.xml | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 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 19c765ef5d..dade43a98b 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 @@ -36,7 +36,7 @@ - + @@ -56,7 +56,7 @@ - + @@ -70,9 +70,14 @@ - + + + + + + From 0ab3b690d6d21c636fc93d74fe415bbd5ce1b09a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 22 Nov 2021 09:50:09 +0900 Subject: [PATCH 320/851] fix no ground points topic name (#125) --- 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 916bde22cc..a667ec1dc0 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -466,7 +466,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Best Effort - Value: /sensing/lidar/no_ground/pointcloud + Value: /perception/object_segmentation/pointcloud Use Fixed Frame: true Use rainbow: true Value: true From 9bbeddc98032d1f41aeaa55e47470d33eee11810 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 22 Nov 2021 10:05:01 +0900 Subject: [PATCH 321/851] add feature remover (#124) --- .../detection/lidar_based_detection.launch.xml | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) 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 1c24b475cf..a836c4198f 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 @@ -32,9 +32,14 @@ - + + + + + + From 35a05759963cc98fa8b4528cd5a474b682a6ef81 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 22 Nov 2021 17:09:31 +0900 Subject: [PATCH 322/851] add param (#126) --- .../trajectory_follower/longitudinal_controller.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml index 3f833342ad..abcd4458f0 100644 --- a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml +++ b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml @@ -31,6 +31,8 @@ min_d_effort: 0.0 lpf_vel_error_gain: 0.9 current_vel_threshold_pid_integration: 0.5 + enable_brake_keeping_before_stop: false + brake_keeping_acc: -0.2 # smooth stop state smooth_stop_max_strong_acc: -0.5 From 857e3c6e21d03e906d3bebbaa829db8d08cc1063 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 22 Nov 2021 17:26:55 +0900 Subject: [PATCH 323/851] fix yaml (#127) --- .../config/trajectory_follower/lateral_controller.param.yaml | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/control_launch/config/trajectory_follower/lateral_controller.param.yaml b/control_launch/config/trajectory_follower/lateral_controller.param.yaml index 50c6c5cc0b..d2928e02dd 100644 --- a/control_launch/config/trajectory_follower/lateral_controller.param.yaml +++ b/control_launch/config/trajectory_follower/lateral_controller.param.yaml @@ -4,7 +4,6 @@ # -- 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 use_steer_prediction: false # flag for using steer prediction (do not use steer measurement) admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value @@ -12,7 +11,8 @@ # -- 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) + curvature_smoothing_num_traj: 1 # point-to-point index distance used in curvature calculation (for trajectory): curvature is calculated from three points p(i-num), p(i), p(i+num) + curvature_smoothing_num_ref_steer: 15 # point-to-point index distance used in curvature calculation (for steer command reference): curvature is calculated from three points p(i-num), p(i), p(i+num) # -- mpc optimization -- qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or osqp) @@ -57,7 +57,6 @@ # stop state stop_state_entry_ego_speed: 0.2 stop_state_entry_target_speed: 0.5 - stop_state_keep_stopping_dist: 0.5 # vehicle parameters vehicle: From 5ad5e0deba3cd1d2764d275738094b21db4ebbf2 Mon Sep 17 00:00:00 2001 From: RyuYamamoto Date: Wed, 24 Nov 2021 17:48:53 +0900 Subject: [PATCH 324/851] porting localization (#121) * porting localization * fixed odometry in ekf * fixed vehicle twist topic name --- .../pose_twist_fusion_filter.launch.xml | 11 ++++------- .../launch/twist_estimator/twist_estimator.launch.xml | 7 +++++-- 2 files changed, 9 insertions(+), 9 deletions(-) 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 ba2ee548d8..be07542d16 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 @@ -2,15 +2,13 @@ - - - + - + @@ -25,9 +23,8 @@ - + - - + diff --git a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml index 7bd78ae533..76d0a73dbc 100644 --- a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml +++ b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml @@ -1,8 +1,11 @@ + + + + - - + From ab396e5428b13adef4139a4d9717d923f8deab3c Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 24 Nov 2021 20:31:03 +0900 Subject: [PATCH 325/851] Update traffic light type for api relay (#130) --- .../launch/include/internal_api_relay.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_api_launch/launch/include/internal_api_relay.launch.xml b/autoware_api_launch/launch/include/internal_api_relay.launch.xml index bb3bd72a5b..5874fbaf52 100644 --- a/autoware_api_launch/launch/include/internal_api_relay.launch.xml +++ b/autoware_api_launch/launch/include/internal_api_relay.launch.xml @@ -4,7 +4,7 @@ - + From b760257adf06041ca411aa9f6319b30a3efb7b04 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 25 Nov 2021 10:57:52 +0900 Subject: [PATCH 326/851] support x1 perception config (#129) * support x1 perception config * remove product config * update launch.py * maintain some filters params in yaml file * add function to create elevation map pipeline * add param to yaml --- autoware_launch/launch/autoware.launch.xml | 1 - .../launch/logging_simulator.launch.xml | 1 - .../aip_x2_perception.param.yaml | 3 - .../aip_xx1_perception.param.yaml | 3 - .../ground_segmentation.param.yaml | 22 ++ .../ground_segmentation.launch.py | 249 ++++++++++++++---- .../launch/perception.launch.xml | 2 - perception_launch/package.xml | 2 + 8 files changed, 229 insertions(+), 54 deletions(-) delete mode 100644 perception_launch/config/object_segmentation/ground_segmentation/aip_x2_perception.param.yaml delete mode 100644 perception_launch/config/object_segmentation/ground_segmentation/aip_xx1_perception.param.yaml create mode 100644 perception_launch/config/object_segmentation/ground_segmentation/ground_segmentation.param.yaml diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 749881c937..f724e170e0 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -49,7 +49,6 @@ - diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 612258a334..20feb42538 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -75,7 +75,6 @@ - diff --git a/perception_launch/config/object_segmentation/ground_segmentation/aip_x2_perception.param.yaml b/perception_launch/config/object_segmentation/ground_segmentation/aip_x2_perception.param.yaml deleted file mode 100644 index e327ec3f1c..0000000000 --- a/perception_launch/config/object_segmentation/ground_segmentation/aip_x2_perception.param.yaml +++ /dev/null @@ -1,3 +0,0 @@ -/**: - ros__parameters: - additional_lidars: ["front_upper", "front_lower"] diff --git a/perception_launch/config/object_segmentation/ground_segmentation/aip_xx1_perception.param.yaml b/perception_launch/config/object_segmentation/ground_segmentation/aip_xx1_perception.param.yaml deleted file mode 100644 index 8723b3b263..0000000000 --- a/perception_launch/config/object_segmentation/ground_segmentation/aip_xx1_perception.param.yaml +++ /dev/null @@ -1,3 +0,0 @@ -/**: - ros__parameters: - additional_lidars: [] diff --git a/perception_launch/config/object_segmentation/ground_segmentation/ground_segmentation.param.yaml b/perception_launch/config/object_segmentation/ground_segmentation/ground_segmentation.param.yaml new file mode 100644 index 0000000000..67affead0e --- /dev/null +++ b/perception_launch/config/object_segmentation/ground_segmentation/ground_segmentation.param.yaml @@ -0,0 +1,22 @@ +/**: + ros__parameters: + additional_lidars: [] + use_ransac_pipeline: False + use_compare_map_pipeline: False + + common_crop_box_filter: + parameters: + min_x: -50.0 + max_x: 100.0 + min_y: -50.0 + max_y: 50.0 + negative: False + + common_ground_filter: + plugin: "ground_segmentation::ScanGroundFilterComponent" + parameters: + global_slope_max_angle_deg: 10.0 + local_slope_max_angle_deg: 30.0 + split_points_distance_tolerance: 0.2 + split_height_distance: 0.2 + use_virtual_ground_point: False diff --git a/perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py index cc3906fe09..837429c831 100644 --- a/perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -11,7 +11,9 @@ # 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 +from ament_index_python.packages import get_package_share_directory import launch from launch.actions import DeclareLaunchArgument from launch.actions import IncludeLaunchDescription @@ -50,7 +52,7 @@ def get_vehicle_mirror_info(context): return p -def create_additional_pipeline(vehicle_info, lidar_name): +def create_additional_pipeline(vehicle_info, lidar_name, ground_segmentation_param): crop_box_filter_component = ComposableNode( package="pointcloud_preprocessor", plugin="pointcloud_preprocessor::CropBoxFilterComponent", @@ -63,51 +65,192 @@ def create_additional_pipeline(vehicle_info, lidar_name): { "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, - } + }, + ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"], ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) ground_filter_component = ComposableNode( package="ground_segmentation", - plugin="ground_segmentation::ScanGroundFilterComponent", - name=f"{lidar_name}_scan_ground_filter", + plugin=ground_segmentation_param[f"{lidar_name}_ground_filter"]["plugin"], + name=f"{lidar_name}_ground_filter", remappings=[ ("input", f"{lidar_name}/measurement_range_cropped/pointcloud"), ("output", f"{lidar_name}/no_ground/pointcloud"), ], + parameters=[ground_segmentation_param[f"{lidar_name}_ground_filter"]["parameters"]], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + return [crop_box_filter_component, ground_filter_component] + + +def create_ransac_pipeline(ground_segmentation_param): + livox_concat_component = ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + name="livox_concatenate_data", + remappings=[("output", "livox_concatenated/pointcloud")], parameters=[ { - "global_slope_max_angle_deg": 10.0, - "local_slope_max_angle_deg": 30.0, - "split_points_distance_tolerance": 0.1, - "split_height_distance": 0.05, + "input_topics": [ + "/sensing/lidar/front_left/min_range_cropped/pointcloud", + "/sensing/lidar/front_right/min_range_cropped/pointcloud", + "/sensing/lidar/front_center/min_range_cropped/pointcloud", + ], + "output_frame": LaunchConfiguration("base_frame"), + "timeout_sec": 1.0, } ], + ) + + short_height_obstacle_detection_area_filter_component = ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::CropBoxFilterComponent", + name="short_height_obstacle_detection_area_filter", + remappings=[ + ("input", "livox_concatenated/pointcloud"), + ("output", "short_height_obstacle_detection_area/pointcloud"), + ], + parameters=[ + { + "input_frame": LaunchConfiguration("base_frame"), + "output_frame": LaunchConfiguration("base_frame"), + }, + ground_segmentation_param["short_height_obstacle_detection_area_filter"]["parameters"], + ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - return [crop_box_filter_component, ground_filter_component] + vector_map_filter_component = ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::Lanelet2MapFilterComponent", + name="vector_map_filter", + remappings=[ + ("input/pointcloud", "short_height_obstacle_detection_area/pointcloud"), + ("input/vector_map", "/map/vector_map"), + ("output", "vector_map_filtered/pointcloud"), + ], + parameters=[ + { + "voxel_size_x": 0.25, + "voxel_size_y": 0.25, + } + ], + # cannot use intra process because vector map filter uses transient local. + extra_arguments=[{"use_intra_process_comms": False}], + ) + + ransac_ground_filter_component = ComposableNode( + package="ground_segmentation", + plugin="ground_segmentation::RANSACGroundFilterComponent", + name="ransac_ground_filter", + remappings=[ + ("input", "vector_map_filtered/pointcloud"), + ("output", "short_height/no_ground/pointcloud"), + ], + parameters=[ground_segmentation_param["ransac_ground_filter"]["parameters"]], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + return [ + livox_concat_component, + short_height_obstacle_detection_area_filter_component, + vector_map_filter_component, + ransac_ground_filter_component, + ] + + +def create_elevation_map_filter_pipeline(): + compare_elevation_map_filter_component = ComposableNode( + package="compare_map_segmentation", + plugin="compare_map_segmentation::CompareElevationMapFilterComponent", + name="compare_elevation_map_filter", + remappings=[ + ("input", "no_ground/oneshot/pointcloud"), + ("output", "map_filtered/pointcloud"), + ("input/elevation_map", "/map/elevation_map"), + ], + parameters=[ + { + "map_frame": "map", + "map_layer_name": "elevation", + "height_diff_thresh": 0.15, + "input_frame": "map", + "output_frame": "base_link", + } + ], + extra_arguments=[{"use_intra_process_comms": False}], # can't use this with transient_local + ) + + downsampling_component = ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", + name="voxel_grid_filter", + remappings=[ + ("input", "map_filtered/pointcloud"), + ("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, + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + voxel_grid_outlier_filter_component = ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::VoxelGridOutlierFilterComponent", + name="voxel_grid_outlier_filter", + remappings=[ + ("input", "voxel_grid_filtered/pointcloud"), + ("output", "/perception/object_segmentation/pointcloud"), + ], + parameters=[ + { + "voxel_size_x": 0.4, + "voxel_size_y": 0.4, + "voxel_size_z": 100.0, + "voxel_points_threshold": 5, + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + return [ + compare_elevation_map_filter_component, + downsampling_component, + voxel_grid_outlier_filter_component, + ] def launch_setup(context, *args, **kwargs): vehicle_info = get_vehicle_info(context) - path = LaunchConfiguration("perception_config_file").perform(context) - with open(path, "r") as f: - pipeline_param = yaml.safe_load(f)["/**"]["ros__parameters"] + ground_segmentation_param_path = os.path.join( + get_package_share_directory("perception_launch"), + "config/object_segmentation/ground_segmentation/ground_segmentation.param.yaml", + ) + with open(ground_segmentation_param_path, "r") as f: + ground_segmentation_param = yaml.safe_load(f)["/**"]["ros__parameters"] additional_pipeline_components = [] - for lidar_name in pipeline_param["additional_lidars"]: - additional_pipeline_components.extend(create_additional_pipeline(vehicle_info, lidar_name)) + if ground_segmentation_param["use_ransac_pipeline"]: + additional_pipeline_components = create_ransac_pipeline(ground_segmentation_param) + else: + for lidar_name in ground_segmentation_param["additional_lidars"]: + additional_pipeline_components.extend( + create_additional_pipeline(vehicle_info, lidar_name, ground_segmentation_param) + ) crop_box_filter_component = ComposableNode( package="pointcloud_preprocessor", @@ -121,40 +264,28 @@ def launch_setup(context, *args, **kwargs): { "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, - } + }, + ground_segmentation_param["common_crop_box_filter"]["parameters"], ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) ground_filter_component = ComposableNode( package="ground_segmentation", - plugin="ground_segmentation::ScanGroundFilterComponent", - name="scan_ground_filter", + plugin=ground_segmentation_param["common_ground_filter"]["plugin"], + name="common_ground_filter", remappings=[ ("input", "measurement_range_cropped/pointcloud"), ("output", "no_ground/pointcloud"), ], - parameters=[ - { - "global_slope_max_angle_deg": 10.0, - "local_slope_max_angle_deg": 30.0, - "split_points_distance_tolerance": 0.2, - "split_height_distance": 0.2, - "use_virtual_ground_point": False, - } - ], + parameters=[ground_segmentation_param["common_ground_filter"]["parameters"]], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) ground_concat_topics = ["no_ground/pointcloud"] - for lidar_name in pipeline_param["additional_lidars"]: + for lidar_name in ground_segmentation_param["additional_lidars"]: ground_concat_topics.extend([f"{lidar_name}/no_ground/pointcloud"]) concat_data_component = ComposableNode( @@ -181,15 +312,21 @@ def launch_setup(context, *args, **kwargs): launch_arguments={ "container": "/perception/object_segmentation/ground_segmentation/perception_pipeline_container", "input/obstacle_pointcloud": "no_ground/oneshot/pointcloud" - if bool(pipeline_param["additional_lidars"]) + if bool(ground_segmentation_param["additional_lidars"]) else "no_ground/pointcloud", "input/raw_pointcloud": "/sensing/lidar/concatenated/pointcloud", "output": "occupancy_grid", "use_intra_process": LaunchConfiguration("use_intra_process"), }.items(), + condition=UnlessCondition( + LaunchConfiguration( + "use_compare_map_pipeline", + default=ground_segmentation_param["use_compare_map_pipeline"], + ) + ), ) - occupancy_grid_map_outlier_component = ComposableNode( + occupancy_outlier_filter_component = ComposableNode( package="pointcloud_preprocessor", plugin="pointcloud_preprocessor::OccupancyGridMapOutlierFilterComponent", name="occupancy_grid_map_outlier_filter", @@ -198,7 +335,7 @@ def launch_setup(context, *args, **kwargs): ( "~/input/pointcloud", "no_ground/oneshot/pointcloud" - if bool(pipeline_param["additional_lidars"]) + if bool(ground_segmentation_param["additional_lidars"]) else "no_ground/pointcloud", ), ("~/output/pointcloud", "/perception/object_segmentation/pointcloud"), @@ -215,7 +352,6 @@ def launch_setup(context, *args, **kwargs): composable_node_descriptions=[ crop_box_filter_component, ground_filter_component, - occupancy_grid_map_outlier_component, ], output="screen", ) @@ -225,7 +361,8 @@ def launch_setup(context, *args, **kwargs): target_container=container, condition=IfCondition( LaunchConfiguration( - "use_additional_pipeline", default=bool(pipeline_param["additional_lidars"]) + "use_additional_pipeline", + default=bool(ground_segmentation_param["additional_lidars"]), ) ), ) @@ -235,7 +372,30 @@ def launch_setup(context, *args, **kwargs): target_container=container, condition=IfCondition( LaunchConfiguration( - "use_additional_pipeline", default=bool(pipeline_param["additional_lidars"]) + "use_additional_pipeline", + default=bool(ground_segmentation_param["additional_lidars"]), + ) + ), + ) + + compare_map_component_loader = LoadComposableNodes( + composable_node_descriptions=create_elevation_map_filter_pipeline(), + target_container=container, + condition=IfCondition( + LaunchConfiguration( + "use_compare_map_pipeline", + default=ground_segmentation_param["use_compare_map_pipeline"], + ) + ), + ) + + occupancy_grid_outlier_filter_component_loader = LoadComposableNodes( + composable_node_descriptions=[occupancy_outlier_filter_component], + target_container=container, + condition=UnlessCondition( + LaunchConfiguration( + "use_compare_map_pipeline", + default=ground_segmentation_param["use_compare_map_pipeline"], ) ), ) @@ -243,7 +403,9 @@ def launch_setup(context, *args, **kwargs): return [ container, additional_pipeline_loader, + compare_map_component_loader, concat_data_component_loader, + occupancy_grid_outlier_filter_component_loader, laserscan_to_occupancy_grid_map_loader, ] @@ -257,7 +419,6 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("base_frame", "base_link") add_launch_arg("vehicle_param_file") - add_launch_arg("perception_config_file") add_launch_arg("use_multithread", "False") add_launch_arg("use_intra_process", "True") diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 65bc16c8e0..924b7ea3ea 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -2,7 +2,6 @@ - @@ -40,7 +39,6 @@ - diff --git a/perception_launch/package.xml b/perception_launch/package.xml index 865d3c4b71..eda35c97c3 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -10,6 +10,7 @@ ament_cmake_auto + compare_map_segmentation euclidean_cluster image_transport_decompressor lidar_apollo_instance_segmentation @@ -17,6 +18,7 @@ multi_object_tracker object_merger object_range_splitter + object_segmentation roi_cluster_fusion shape_estimation tensorrt_yolo From 1974743b288417bad4723ab45634fe15fbd4432e Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 25 Nov 2021 13:00:56 +0900 Subject: [PATCH 327/851] Update traffic light topic name (#131) * Update traffic light topic name Signed-off-by: wep21 * Update traffic light topic name in perception Signed-off-by: wep21 --- .../launch/include/internal_api_relay.launch.xml | 6 +++--- .../traffic_light_node_container.launch.py | 4 ++-- .../behavior_planning/behavior_planning.launch.py | 10 +++++----- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/autoware_api_launch/launch/include/internal_api_relay.launch.xml b/autoware_api_launch/launch/include/internal_api_relay.launch.xml index 5874fbaf52..46859d0fbd 100644 --- a/autoware_api_launch/launch/include/internal_api_relay.launch.xml +++ b/autoware_api_launch/launch/include/internal_api_relay.launch.xml @@ -1,9 +1,9 @@ - - - + + + 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 d048743b80..8993530343 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 @@ -117,7 +117,7 @@ def create_parameter_dict(*args): remappings=[ ("~/input/image", LaunchConfiguration("input/image")), ("~/input/rois", "rois"), - ("~/output/traffic_light_states", "traffic_light_states"), + ("~/output/traffic_signals", "traffic_signals"), ], extra_arguments=[ {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} @@ -132,7 +132,7 @@ def create_parameter_dict(*args): ("~/input/image", LaunchConfiguration("input/image")), ("~/input/rois", "rois"), ("~/input/rough/rois", "rough/rois"), - ("~/input/traffic_light_states", "traffic_light_states"), + ("~/input/traffic_signals", "traffic_signals"), ("~/output/image", "debug/rois"), ("~/output/image/compressed", "debug/rois/compressed"), ("~/output/image/compressedDepth", "debug/rois/compressedDepth"), diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 88bb6b419a..1e56ec6beb 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -263,12 +263,12 @@ def generate_launch_description(): ("~/input/dynamic_objects", "/perception/object_recognition/objects"), ("~/input/no_ground_pointcloud", "/sensing/lidar/no_ground/pointcloud"), ( - "~/input/traffic_light_states", - "/perception/traffic_light_recognition/traffic_light_states", + "~/input/traffic_signals", + "/perception/traffic_light_recognition/traffic_signals", ), ( - "~/input/external_traffic_light_states", - "/external/traffic_light_recognition/traffic_light_states", + "~/input/external_traffic_signals", + "/external/traffic_light_recognition/traffic_signals", ), ("~/input/virtual_traffic_light_states", "/awapi/tmp/virtual_traffic_light_states"), ("~/input/occupancy_grid", "/sensing/lidar/occupancy_grid"), @@ -278,7 +278,7 @@ def generate_launch_description(): "~/output/infrastructure_commands", "/planning/scenario_planning/status/infrastructure_commands", ), - ("~/output/traffic_light_state", "debug/traffic_light_state"), + ("~/output/traffic_signal", "debug/traffic_signal"), ], parameters=[ { From 808b363f87e8bd1c419abba75c8e9ac99b7cc63d Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 25 Nov 2021 14:41:31 +0900 Subject: [PATCH 328/851] Fix exec depend in perception launch (#132) Signed-off-by: wep21 --- perception_launch/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception_launch/package.xml b/perception_launch/package.xml index eda35c97c3..37ac98bb9c 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -12,13 +12,13 @@ compare_map_segmentation euclidean_cluster + ground_segmentation image_transport_decompressor lidar_apollo_instance_segmentation map_based_prediction multi_object_tracker object_merger object_range_splitter - object_segmentation roi_cluster_fusion shape_estimation tensorrt_yolo From b2283c42cfd41dede2ff2be58c602b9d0e6003e5 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 25 Nov 2021 16:59:11 +0900 Subject: [PATCH 329/851] Fix no ground pointcloud topic name (#134) Signed-off-by: j4tfwm6z Co-authored-by: j4tfwm6z --- .../behavior_planning/behavior_planning.launch.py | 5 ++++- .../motion_planning/motion_planning.launch.py | 10 ++++++++-- .../motion_planning/motion_planning.launch.xml | 2 +- .../launch/scenario_planning/parking.launch.py | 5 ++++- .../launch/scenario_planning/parking.launch.xml | 2 +- 5 files changed, 18 insertions(+), 6 deletions(-) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 1e56ec6beb..ce39509db4 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -261,7 +261,10 @@ def generate_launch_description(): ("~/input/vector_map", "/map/vector_map"), ("~/input/vehicle_odometry", "/localization/kinematic_state"), ("~/input/dynamic_objects", "/perception/object_recognition/objects"), - ("~/input/no_ground_pointcloud", "/sensing/lidar/no_ground/pointcloud"), + ( + "~/input/no_ground_pointcloud", + "/perception/object_segmentation/pointcloud", + ), ( "~/input/traffic_signals", "/perception/traffic_light_recognition/traffic_signals", diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index 4c06a7b8c0..0fa0c4debf 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -90,7 +90,10 @@ def generate_launch_description(): ("~/output/no_start_reason", "/planning/scenario_planning/status/no_start_reason"), ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), ("~/output/trajectory", "surround_obstacle_checker/trajectory"), - ("~/input/pointcloud", "/sensing/lidar/no_ground/pointcloud"), + ( + "~/input/pointcloud", + "/perception/object_segmentation/pointcloud", + ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), @@ -154,7 +157,10 @@ def generate_launch_description(): "/planning/scenario_planning/clear_velocity_limit", ), ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), - ("~/input/pointcloud", "/sensing/lidar/no_ground/pointcloud"), + ( + "~/input/pointcloud", + "/perception/object_segmentation/pointcloud", + ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), ("~/input/trajectory", "surround_obstacle_checker/trajectory"), 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 4e0ee98c72..6ede637e48 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 @@ -43,7 +43,7 @@ - + diff --git a/planning_launch/launch/scenario_planning/parking.launch.py b/planning_launch/launch/scenario_planning/parking.launch.py index fef7775518..c501190363 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.py +++ b/planning_launch/launch/scenario_planning/parking.launch.py @@ -52,7 +52,10 @@ def generate_launch_description(): name="costmap_generator", remappings=[ ("~/input/objects", "/perception/object_recognition/objects"), - ("~/input/points_no_ground", "/sensing/lidar/no_ground/pointcloud"), + ( + "~/input/points_no_ground", + "/perception/object_segmentation/pointcloud", + ), ("~/input/vector_map", "/map/vector_map"), ("~/input/scenario", "/planning/scenario_planning/scenario"), ("~/output/grid_map", "costmap_generator/grid_map"), diff --git a/planning_launch/launch/scenario_planning/parking.launch.xml b/planning_launch/launch/scenario_planning/parking.launch.xml index 2465dac51f..6add04ef8e 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.xml +++ b/planning_launch/launch/scenario_planning/parking.launch.xml @@ -4,7 +4,7 @@ - + From f46e16d6fa91b77ac70200918af37080c462f5c9 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 29 Nov 2021 08:47:03 +0900 Subject: [PATCH 330/851] fix/rviz perception config (#138) --- autoware_launch/rviz/autoware.rviz | 70 ++++++++++++++++-------------- 1 file changed, 37 insertions(+), 33 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index a667ec1dc0..1cc02a6a98 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -437,39 +437,6 @@ Visualization Manager: Use Fixed Frame: false Use rainbow: true Value: true - - Alpha: 0.999 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 15 - Min Value: -2 - Value: false - Axis: Z - Channel Name: z - Class: rviz_default_plugins/PointCloud2 - Color: 200; 200; 200 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 15 - Min Color: 0; 0; 0 - Min Intensity: -5 - Name: NoGroundPointCloud - Position Transformer: XYZ - Selectable: true - Size (Pixels): 3 - Size (m): 0.02 - Style: Points - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_segmentation/pointcloud - Use Fixed Frame: true - Use rainbow: true - Value: true - Alpha: 0.999 Class: rviz_default_plugins/Polygon Color: 25; 255; 0 @@ -716,6 +683,43 @@ Visualization Manager: Name: Localization - Class: rviz_common/Group Displays: + - Class: rviz_common/Group + Displays: + - Alpha: 0.999 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 15 + Min Value: -2 + Value: false + Axis: Z + Channel Name: z + Class: rviz_default_plugins/PointCloud2 + Color: 200; 200; 200 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 15 + Min Color: 0; 0; 0 + Min Intensity: -5 + Name: NoGroundPointCloud + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.02 + Style: Points + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_segmentation/pointcloud + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Name: Segmentation - Class: rviz_common/Group Displays: - BUS: From cf3bfc4322e320f72daef4cc64f68385fe26d83e Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 29 Nov 2021 13:30:40 +0900 Subject: [PATCH 331/851] auto/fix occupancy grid map topic name (#137) --- .../ground_segmentation/ground_segmentation.launch.py | 4 ++-- .../behavior_planning/behavior_planning.launch.py | 5 ++++- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py index 837429c831..ab7b9a3afc 100644 --- a/perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -315,7 +315,7 @@ def launch_setup(context, *args, **kwargs): if bool(ground_segmentation_param["additional_lidars"]) else "no_ground/pointcloud", "input/raw_pointcloud": "/sensing/lidar/concatenated/pointcloud", - "output": "occupancy_grid", + "output": "/perception/occupancy_grid_map/map", "use_intra_process": LaunchConfiguration("use_intra_process"), }.items(), condition=UnlessCondition( @@ -331,7 +331,7 @@ def launch_setup(context, *args, **kwargs): plugin="pointcloud_preprocessor::OccupancyGridMapOutlierFilterComponent", name="occupancy_grid_map_outlier_filter", remappings=[ - ("~/input/occupancy_grid_map", "occupancy_grid"), + ("~/input/occupancy_grid_map", "/perception/occupancy_grid_map/map"), ( "~/input/pointcloud", "no_ground/oneshot/pointcloud" diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index ce39509db4..4b000729c2 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -274,7 +274,10 @@ def generate_launch_description(): "/external/traffic_light_recognition/traffic_signals", ), ("~/input/virtual_traffic_light_states", "/awapi/tmp/virtual_traffic_light_states"), - ("~/input/occupancy_grid", "/sensing/lidar/occupancy_grid"), + ( + "~/input/occupancy_grid", + "/perception/occupancy_grid_map/map", + ), ("~/output/path", "path"), ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), ( From 99528b0ecdc056ae551dc6dec8318ad31b7c1209 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 29 Nov 2021 14:32:09 +0900 Subject: [PATCH 332/851] fix/rename segmentation namespace (#139) * fix namespace: rviz config * fix namespace: planning stack * rename segmentatino directory * fix namespace: perception stack --- autoware_launch/rviz/autoware.rviz | 2 +- .../ground_segmentation/ground_segmentation.param.yaml | 0 .../ground_segmentation/ground_segmentation.launch.py | 8 ++++---- perception_launch/launch/perception.launch.xml | 4 ++-- .../behavior_planning/behavior_planning.launch.py | 2 +- .../motion_planning/motion_planning.launch.py | 4 ++-- .../motion_planning/motion_planning.launch.xml | 2 +- .../launch/scenario_planning/parking.launch.py | 2 +- .../launch/scenario_planning/parking.launch.xml | 2 +- 9 files changed, 13 insertions(+), 13 deletions(-) rename perception_launch/config/{object_segmentation => obstacle_segmentation}/ground_segmentation/ground_segmentation.param.yaml (100%) rename perception_launch/launch/{object_segmentation => obstacle_segmentation}/ground_segmentation/ground_segmentation.launch.py (97%) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 1cc02a6a98..d82f6deec4 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -714,7 +714,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Best Effort - Value: /perception/object_segmentation/pointcloud + Value: /perception/obstacle_segmentation/pointcloud Use Fixed Frame: true Use rainbow: true Value: true diff --git a/perception_launch/config/object_segmentation/ground_segmentation/ground_segmentation.param.yaml b/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml similarity index 100% rename from perception_launch/config/object_segmentation/ground_segmentation/ground_segmentation.param.yaml rename to perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml diff --git a/perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py similarity index 97% rename from perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py rename to perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index ab7b9a3afc..8bd6345ad8 100644 --- a/perception_launch/launch/object_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -212,7 +212,7 @@ def create_elevation_map_filter_pipeline(): name="voxel_grid_outlier_filter", remappings=[ ("input", "voxel_grid_filtered/pointcloud"), - ("output", "/perception/object_segmentation/pointcloud"), + ("output", "/perception/obstacle_segmentation/pointcloud"), ], parameters=[ { @@ -238,7 +238,7 @@ def launch_setup(context, *args, **kwargs): ground_segmentation_param_path = os.path.join( get_package_share_directory("perception_launch"), - "config/object_segmentation/ground_segmentation/ground_segmentation.param.yaml", + "config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml", ) with open(ground_segmentation_param_path, "r") as f: ground_segmentation_param = yaml.safe_load(f)["/**"]["ros__parameters"] @@ -310,7 +310,7 @@ def launch_setup(context, *args, **kwargs): ] ), launch_arguments={ - "container": "/perception/object_segmentation/ground_segmentation/perception_pipeline_container", + "container": "/perception/obstacle_segmentation/ground_segmentation/perception_pipeline_container", "input/obstacle_pointcloud": "no_ground/oneshot/pointcloud" if bool(ground_segmentation_param["additional_lidars"]) else "no_ground/pointcloud", @@ -338,7 +338,7 @@ def launch_setup(context, *args, **kwargs): if bool(ground_segmentation_param["additional_lidars"]) else "no_ground/pointcloud", ), - ("~/output/pointcloud", "/perception/object_segmentation/pointcloud"), + ("~/output/pointcloud", "/perception/obstacle_segmentation/pointcloud"), ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 924b7ea3ea..92aca9080c 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -30,11 +30,11 @@ - + - + diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 4b000729c2..1ff96c2244 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -263,7 +263,7 @@ def generate_launch_description(): ("~/input/dynamic_objects", "/perception/object_recognition/objects"), ( "~/input/no_ground_pointcloud", - "/perception/object_segmentation/pointcloud", + "/perception/obstacle_segmentation/pointcloud", ), ( "~/input/traffic_signals", diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index 0fa0c4debf..036ae246f3 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -92,7 +92,7 @@ def generate_launch_description(): ("~/output/trajectory", "surround_obstacle_checker/trajectory"), ( "~/input/pointcloud", - "/perception/object_segmentation/pointcloud", + "/perception/obstacle_segmentation/pointcloud", ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), @@ -159,7 +159,7 @@ def generate_launch_description(): ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), ( "~/input/pointcloud", - "/perception/object_segmentation/pointcloud", + "/perception/obstacle_segmentation/pointcloud", ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), 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 6ede637e48..036b9bcc9f 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 @@ -43,7 +43,7 @@ - + diff --git a/planning_launch/launch/scenario_planning/parking.launch.py b/planning_launch/launch/scenario_planning/parking.launch.py index c501190363..e3d9e750a0 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.py +++ b/planning_launch/launch/scenario_planning/parking.launch.py @@ -54,7 +54,7 @@ def generate_launch_description(): ("~/input/objects", "/perception/object_recognition/objects"), ( "~/input/points_no_ground", - "/perception/object_segmentation/pointcloud", + "/perception/obstacle_segmentation/pointcloud", ), ("~/input/vector_map", "/map/vector_map"), ("~/input/scenario", "/planning/scenario_planning/scenario"), diff --git a/planning_launch/launch/scenario_planning/parking.launch.xml b/planning_launch/launch/scenario_planning/parking.launch.xml index 6add04ef8e..9fbf153549 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.xml +++ b/planning_launch/launch/scenario_planning/parking.launch.xml @@ -4,7 +4,7 @@ - + From 58419a9144aa48b65a5238bbdcae4180de8b63b3 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 30 Nov 2021 13:38:29 +0900 Subject: [PATCH 333/851] fix/add arg in order to disable dummy_perception_publisher from command line (#144) --- autoware_launch/launch/logging_simulator.launch.xml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 20feb42538..8ded2046f0 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -20,6 +20,8 @@ + + @@ -109,7 +111,7 @@ - + From 0efb63d0e6cb9cca047354b44a72ad917d657b76 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 2 Dec 2021 14:31:47 +0900 Subject: [PATCH 334/851] fix/move occupancy grid map outlier filter (#143) * fix package name * add occupancy grid map launch * update launcher * rename filter package --- .../ground_segmentation.launch.py | 32 +--- .../occupancy_grid_map.launch.py | 139 ++++++++++++++++++ .../launch/perception.launch.xml | 10 ++ perception_launch/package.xml | 2 + 4 files changed, 153 insertions(+), 30 deletions(-) create mode 100644 perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 8bd6345ad8..065a6fb9e3 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -16,17 +16,14 @@ from ament_index_python.packages import get_package_share_directory import launch from launch.actions import DeclareLaunchArgument -from launch.actions import IncludeLaunchDescription from launch.actions import OpaqueFunction from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition from launch.conditions import UnlessCondition -from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode -from launch_ros.substitutions import FindPackageShare import yaml @@ -302,33 +299,9 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - laserscan_to_occupancy_grid_map_loader = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - [ - FindPackageShare("laserscan_to_occupancy_grid_map"), - "/launch/laserscan_to_occupancy_grid_map.launch.py", - ] - ), - launch_arguments={ - "container": "/perception/obstacle_segmentation/ground_segmentation/perception_pipeline_container", - "input/obstacle_pointcloud": "no_ground/oneshot/pointcloud" - if bool(ground_segmentation_param["additional_lidars"]) - else "no_ground/pointcloud", - "input/raw_pointcloud": "/sensing/lidar/concatenated/pointcloud", - "output": "/perception/occupancy_grid_map/map", - "use_intra_process": LaunchConfiguration("use_intra_process"), - }.items(), - condition=UnlessCondition( - LaunchConfiguration( - "use_compare_map_pipeline", - default=ground_segmentation_param["use_compare_map_pipeline"], - ) - ), - ) - occupancy_outlier_filter_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::OccupancyGridMapOutlierFilterComponent", + package="occupancy_grid_map_outlier_filter", + plugin="occupancy_grid_map_outlier_filter::OccupancyGridMapOutlierFilterComponent", name="occupancy_grid_map_outlier_filter", remappings=[ ("~/input/occupancy_grid_map", "/perception/occupancy_grid_map/map"), @@ -406,7 +379,6 @@ def launch_setup(context, *args, **kwargs): compare_map_component_loader, concat_data_component_loader, occupancy_grid_outlier_filter_component_loader, - laserscan_to_occupancy_grid_map_loader, ] diff --git a/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py b/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py new file mode 100644 index 0000000000..fc7b9323ad --- /dev/null +++ b/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py @@ -0,0 +1,139 @@ +# Copyright 2021 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import LaunchConfigurationEquals +from launch.conditions import LaunchConfigurationNotEquals +from launch.conditions import UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes +from launch_ros.descriptions import ComposableNode + + +def generate_launch_description(): + def add_launch_arg(name: str, default_value=None): + return DeclareLaunchArgument(name, default_value=default_value) + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + + composable_nodes = [ + ComposableNode( + package="pointcloud_to_laserscan", + plugin="pointcloud_to_laserscan::PointCloudToLaserScanNode", + name="pointcloud_to_laserscan_node", + remappings=[ + ("~/input/pointcloud", LaunchConfiguration("input/obstacle_pointcloud")), + ("~/output/laserscan", LaunchConfiguration("output/laserscan")), + ("~/output/pointcloud", LaunchConfiguration("output/pointcloud")), + ("~/output/ray", LaunchConfiguration("output/ray")), + ("~/output/stixel", LaunchConfiguration("output/stixel")), + ], + parameters=[ + { + "target_frame": "base_link", # Leave disabled to output scan in pointcloud frame + "transform_tolerance": 0.01, + "min_height": 0.0, + "max_height": 2.0, + "angle_min": -3.141592, # -M_PI + "angle_max": 3.141592, # M_PI + "angle_increment": 0.00436332222, # 0.25*M_PI/180.0 + "scan_time": 0.0, + "range_min": 1.0, + "range_max": 200.0, + "use_inf": True, + "inf_epsilon": 1.0, + # Concurrency level, affects number of pointclouds queued for processing + # and number of threads used + # 0 : Detect number of cores + # 1 : Single threaded + # 2->inf : Parallelism level + "concurrency_level": 1, + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ), + ComposableNode( + package="laserscan_to_occupancy_grid_map", + plugin="occupancy_grid_map::OccupancyGridMapNode", + name="occupancy_grid_map_node", + remappings=[ + ("~/input/laserscan", LaunchConfiguration("output/laserscan")), + ("~/input/obstacle_pointcloud", LaunchConfiguration("input/obstacle_pointcloud")), + ("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")), + ("~/output/occupancy_grid_map", LaunchConfiguration("output")), + ], + parameters=[ + { + "map_resolution": 0.5, + "use_height_filter": True, + "input_obstacle_pointcloud": LaunchConfiguration("input_obstacle_pointcloud"), + "input_obstacle_and_raw_pointcloud": LaunchConfiguration( + "input_obstacle_and_raw_pointcloud" + ), + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ), + ] + + occupancy_grid_map_container = ComposableNodeContainer( + condition=LaunchConfigurationEquals("container", ""), + name="occupancy_grid_map_container", + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=composable_nodes, + output="screen", + ) + + load_composable_nodes = LoadComposableNodes( + condition=LaunchConfigurationNotEquals("container", ""), + composable_node_descriptions=composable_nodes, + target_container=LaunchConfiguration("container"), + ) + + return LaunchDescription( + [ + add_launch_arg("container", ""), + add_launch_arg("use_multithread", "false"), + add_launch_arg("use_intra_process", "false"), + add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"), + add_launch_arg("input/raw_pointcloud", "concatenated/pointcloud"), + add_launch_arg("output", "occupancy_grid"), + add_launch_arg("output/laserscan", "virtual_scan/laserscan"), + add_launch_arg("output/pointcloud", "virtual_scan/pointcloud"), + add_launch_arg("output/ray", "virtual_scan/ray"), + add_launch_arg("output/stixel", "virtual_scan/stixel"), + add_launch_arg("input_obstacle_pointcloud", "false"), + add_launch_arg("input_obstacle_and_raw_pointcloud", "true"), + set_container_executable, + set_container_mt_executable, + occupancy_grid_map_container, + load_composable_nodes, + ] + ) diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 92aca9080c..dcf1498e21 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -43,6 +43,16 @@ + + + + + + + + + + diff --git a/perception_launch/package.xml b/perception_launch/package.xml index 37ac98bb9c..f47fc42182 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -19,6 +19,8 @@ multi_object_tracker object_merger object_range_splitter + occupancy_grid_map_outlier_filter + pointcloud_to_laserscan roi_cluster_fusion shape_estimation tensorrt_yolo From becf3ff493a4c82655e02338565e47acff304eeb Mon Sep 17 00:00:00 2001 From: Taichi Higashide Date: Thu, 2 Dec 2021 15:49:45 +0900 Subject: [PATCH 335/851] input pointcloud_map_path to map_hash_generator (#142) --- map_launch/launch/map.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/map_launch/launch/map.launch.py b/map_launch/launch/map.launch.py index 910b9a3bd6..a4ae541856 100644 --- a/map_launch/launch/map.launch.py +++ b/map_launch/launch/map.launch.py @@ -33,6 +33,7 @@ def generate_launch_description(): parameters=[ { "lanelet2_map_path": LaunchConfiguration("lanelet2_map_path"), + "pointcloud_map_path": LaunchConfiguration("pointcloud_map_path"), } ], ) From d50be70dd838f94e2cea9f695c1b5d5fa512687e Mon Sep 17 00:00:00 2001 From: Sugatyon <32741405+Sugatyon@users.noreply.github.com> Date: Thu, 2 Dec 2021 17:42:12 +0900 Subject: [PATCH 336/851] change topic name for predicted trajectory (#145) --- 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 d82f6deec4..9074177c8a 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1385,7 +1385,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /control/trajectory_follower/predicted_trajectory + Value: /control/trajectory_follower/lateral/predicted_trajectory Value: true View Path: Alpha: 1 From 0da4ddf06891b33a4ce46bb05e56853e4adbfb84 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 2 Dec 2021 22:29:19 +0900 Subject: [PATCH 337/851] fix/add pointcloud_preprocessor depend (#146) --- perception_launch/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/perception_launch/package.xml b/perception_launch/package.xml index f47fc42182..bf643b5c10 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -20,6 +20,7 @@ object_merger object_range_splitter occupancy_grid_map_outlier_filter + pointcloud_preprocessor pointcloud_to_laserscan roi_cluster_fusion shape_estimation From 4df2315074683cd216a75e6ef795e84ef313153c Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Fri, 3 Dec 2021 12:38:30 +0900 Subject: [PATCH 338/851] Fix for api integration test (#140) * Add backward compatibility of autoware state * Rename adaptor class * Rename adaptor class --- .../launch/include/internal_api_adaptor.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py index 4a64f42a85..4b8513f544 100644 --- a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py @@ -35,6 +35,7 @@ def generate_launch_description(): } components = [ _create_api_node("initial_pose", "InitialPose", parameters=[param_initial_pose]), + _create_api_node("iv_msgs", "IVMsgs"), _create_api_node("operator", "Operator"), _create_api_node("route", "Route"), _create_api_node("velocity", "Velocity"), From eaba97f3ed1d7a995ae90ad3fd32a401bd0af10d Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 6 Dec 2021 14:21:41 +0900 Subject: [PATCH 339/851] fix/add use_intra_process_comm option (#148) --- .../ground_segmentation/ground_segmentation.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 065a6fb9e3..f5b2c1d2cb 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -102,6 +102,7 @@ def create_ransac_pipeline(ground_segmentation_param): "timeout_sec": 1.0, } ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) short_height_obstacle_detection_area_filter_component = ComposableNode( From 1102582975cdcb558bf16e203120aa2374291b11 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 6 Dec 2021 15:33:42 +0900 Subject: [PATCH 340/851] feature/use common pointcloud container (#147) * add container argument * load composable node to pointcloud_container * fix autoware_launch * enable multi-thread * improve readability --- autoware_launch/launch/autoware.launch.xml | 12 ++++ .../launch/logging_simulator.launch.xml | 12 ++++ .../launch/pointcloud_container.launch.py | 57 +++++++++++++++++++ .../ground_segmentation.launch.py | 29 ++++++++-- .../occupancy_grid_map.launch.py | 13 ++--- .../launch/perception.launch.xml | 8 +++ sensing_launch/launch/sensing.launch.xml | 4 ++ 7 files changed, 123 insertions(+), 12 deletions(-) create mode 100644 autoware_launch/launch/pointcloud_container.launch.py diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index f724e170e0..5351d3f9fd 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -4,6 +4,8 @@ + + @@ -14,6 +16,12 @@ + + + + + + @@ -38,6 +46,8 @@ + + @@ -49,6 +59,8 @@ + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 8ded2046f0..f23ef0132c 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -20,6 +20,8 @@ + + @@ -29,6 +31,12 @@ + + + + + + @@ -62,6 +70,8 @@ + + @@ -77,6 +87,8 @@ + + diff --git a/autoware_launch/launch/pointcloud_container.launch.py b/autoware_launch/launch/pointcloud_container.launch.py new file mode 100644 index 0000000000..87c46bce69 --- /dev/null +++ b/autoware_launch/launch/pointcloud_container.launch.py @@ -0,0 +1,57 @@ +# Copyright 2021 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer + + +def generate_launch_description(): + def add_launch_arg(name: str, default_value=None): + return DeclareLaunchArgument(name, default_value=default_value) + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + + pointcloud_container = ComposableNodeContainer( + name=LaunchConfiguration("container_name"), + namespace="/", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=[], + output="screen", + ) + + return LaunchDescription( + [ + add_launch_arg("use_multithread", "false"), + add_launch_arg("container_name", "pointcloud_container"), + set_container_executable, + set_container_mt_executable, + pointcloud_container, + ] + ) diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index f5b2c1d2cb..4657278438 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -319,7 +319,7 @@ def launch_setup(context, *args, **kwargs): # set container to run all required components in the same process container = ComposableNodeContainer( - name="perception_pipeline_container", + name=LaunchConfiguration("container_name"), namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), @@ -327,12 +327,28 @@ def launch_setup(context, *args, **kwargs): crop_box_filter_component, ground_filter_component, ], + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), output="screen", ) + composable_nodes_loader = LoadComposableNodes( + composable_node_descriptions=[ + crop_box_filter_component, + ground_filter_component, + ], + target_container=LaunchConfiguration("container_name"), + condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), + ) + + target_container = ( + container + if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) + else LaunchConfiguration("container_name") + ) + additional_pipeline_loader = LoadComposableNodes( composable_node_descriptions=additional_pipeline_components, - target_container=container, + target_container=target_container, condition=IfCondition( LaunchConfiguration( "use_additional_pipeline", @@ -343,7 +359,7 @@ def launch_setup(context, *args, **kwargs): concat_data_component_loader = LoadComposableNodes( composable_node_descriptions=[concat_data_component], - target_container=container, + target_container=target_container, condition=IfCondition( LaunchConfiguration( "use_additional_pipeline", @@ -354,7 +370,7 @@ def launch_setup(context, *args, **kwargs): compare_map_component_loader = LoadComposableNodes( composable_node_descriptions=create_elevation_map_filter_pipeline(), - target_container=container, + target_container=target_container, condition=IfCondition( LaunchConfiguration( "use_compare_map_pipeline", @@ -365,7 +381,7 @@ def launch_setup(context, *args, **kwargs): occupancy_grid_outlier_filter_component_loader = LoadComposableNodes( composable_node_descriptions=[occupancy_outlier_filter_component], - target_container=container, + target_container=target_container, condition=UnlessCondition( LaunchConfiguration( "use_compare_map_pipeline", @@ -376,6 +392,7 @@ def launch_setup(context, *args, **kwargs): return [ container, + composable_nodes_loader, additional_pipeline_loader, compare_map_component_loader, concat_data_component_loader, @@ -394,6 +411,8 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("vehicle_param_file") add_launch_arg("use_multithread", "False") add_launch_arg("use_intra_process", "True") + add_launch_arg("use_pointcloud_container", "False") + add_launch_arg("container_name", "perception_pipeline_container") set_container_executable = SetLaunchConfiguration( "container_executable", diff --git a/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py b/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py index fc7b9323ad..57e172ffda 100644 --- a/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py +++ b/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py @@ -16,8 +16,6 @@ from launch.actions import DeclareLaunchArgument from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition -from launch.conditions import LaunchConfigurationEquals -from launch.conditions import LaunchConfigurationNotEquals from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer @@ -102,24 +100,23 @@ def add_launch_arg(name: str, default_value=None): ] occupancy_grid_map_container = ComposableNodeContainer( - condition=LaunchConfigurationEquals("container", ""), - name="occupancy_grid_map_container", + name=LaunchConfiguration("container_name"), namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), composable_node_descriptions=composable_nodes, + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), output="screen", ) load_composable_nodes = LoadComposableNodes( - condition=LaunchConfigurationNotEquals("container", ""), composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration("container"), + target_container=LaunchConfiguration("container_name"), + condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), ) return LaunchDescription( [ - add_launch_arg("container", ""), add_launch_arg("use_multithread", "false"), add_launch_arg("use_intra_process", "false"), add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"), @@ -131,6 +128,8 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("output/stixel", "virtual_scan/stixel"), add_launch_arg("input_obstacle_pointcloud", "false"), add_launch_arg("input_obstacle_and_raw_pointcloud", "true"), + add_launch_arg("use_pointcloud_container", "False"), + add_launch_arg("container_name", "occupancy_grid_map_container"), set_container_executable, set_container_mt_executable, occupancy_grid_map_container, diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index dcf1498e21..9949fa84ca 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -23,6 +23,8 @@ + + @@ -39,6 +41,8 @@ + + @@ -50,6 +54,10 @@ + + + + diff --git a/sensing_launch/launch/sensing.launch.xml b/sensing_launch/launch/sensing.launch.xml index 8795835878..715b8f9117 100644 --- a/sensing_launch/launch/sensing.launch.xml +++ b/sensing_launch/launch/sensing.launch.xml @@ -4,6 +4,8 @@ + + @@ -15,6 +17,8 @@ + + From 498f86cc3c30ec3cfcf51d5660057ffa846985d9 Mon Sep 17 00:00:00 2001 From: Taichi Higashide Date: Mon, 6 Dec 2021 16:34:18 +0900 Subject: [PATCH 341/851] Add elevation map loader to ground seg launch (#136) --- .../elevation_map_parameters.yaml | 30 +++++++++++ .../ground_segmentation.launch.py | 51 +++++++++++++++++-- 2 files changed, 77 insertions(+), 4 deletions(-) create mode 100644 perception_launch/config/object_segmentation/ground_segmentation/elevation_map_parameters.yaml diff --git a/perception_launch/config/object_segmentation/ground_segmentation/elevation_map_parameters.yaml b/perception_launch/config/object_segmentation/ground_segmentation/elevation_map_parameters.yaml new file mode 100644 index 0000000000..955a9e197e --- /dev/null +++ b/perception_launch/config/object_segmentation/ground_segmentation/elevation_map_parameters.yaml @@ -0,0 +1,30 @@ +pcl_grid_map_extraction: + num_processing_threads: 12 + cloud_transform: + translation: + x: 0.0 + y: 0.0 + z: 0.0 + rotation: #intrinsic rotation X-Y-Z (r-p-y)sequence + r: 0.0 + p: 0.0 + y: 0.0 + cluster_extraction: + cluster_tolerance: 0.2 + min_num_points: 3 + max_num_points: 1000000 + outlier_removal: + is_remove_outliers: false + mean_K: 10 + stddev_threshold: 1.0 + downsampling: + is_downsample_cloud: false + voxel_size: + x: 0.02 + y: 0.02 + z: 0.02 + grid_map: + min_num_points_per_cell: 3 + resolution: 0.3 + height_type: 1 + height_thresh: 1.0 diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 4657278438..9c4b1387ed 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -21,9 +21,11 @@ from launch.conditions import IfCondition from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration +from launch.substitutions import PathJoinSubstitution from launch_ros.actions import ComposableNodeContainer from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode +from launch_ros.substitutions import FindPackageShare import yaml @@ -162,15 +164,53 @@ def create_ransac_pipeline(ground_segmentation_param): ] -def create_elevation_map_filter_pipeline(): +def create_elevation_map_filter_pipeline(ground_segmentation_param): + + elevation_map_loader = ComposableNode( + package="elevation_map_loader", + plugin="ElevationMapLoaderNode", + name="elevation_map_loader", + remappings=[ + ("output/elevation_map", "elevation_map"), + ("input/pointcloud_map", "/map/pointcloud_map"), + ("input/vector_map", "/map/vector_map"), + ], + parameters=[ + { + "use_lane_filter": False, + "use_inpaint": True, + "inpaint_radius": 1.0, + "param_file_path": PathJoinSubstitution( + [ + FindPackageShare("perception_launch"), + "config", + "object_segmentation", + "ground_segmentation", + "elevation_map_parameters.yaml", + ] + ), + "elevation_map_directory": PathJoinSubstitution( + [FindPackageShare("elevation_map_loader"), "data", "elevation_maps"] + ), + "use_elevation_map_cloud_publisher": False, + } + ], + extra_arguments=[{"use_intra_process_comms": False}], + ) + compare_elevation_map_filter_component = ComposableNode( package="compare_map_segmentation", plugin="compare_map_segmentation::CompareElevationMapFilterComponent", name="compare_elevation_map_filter", remappings=[ - ("input", "no_ground/oneshot/pointcloud"), + ( + "input", + "no_ground/oneshot/pointcloud" + if bool(ground_segmentation_param["additional_lidars"]) + else "no_ground/pointcloud", + ), ("output", "map_filtered/pointcloud"), - ("input/elevation_map", "/map/elevation_map"), + ("input/elevation_map", "elevation_map"), ], parameters=[ { @@ -224,6 +264,7 @@ def create_elevation_map_filter_pipeline(): ) return [ + elevation_map_loader, compare_elevation_map_filter_component, downsampling_component, voxel_grid_outlier_filter_component, @@ -369,7 +410,9 @@ def launch_setup(context, *args, **kwargs): ) compare_map_component_loader = LoadComposableNodes( - composable_node_descriptions=create_elevation_map_filter_pipeline(), + composable_node_descriptions=create_elevation_map_filter_pipeline( + ground_segmentation_param + ), target_container=target_container, condition=IfCondition( LaunchConfiguration( From 5488dacf4a16ef66cebdf911f391973a80504968 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Mon, 6 Dec 2021 21:45:22 +0900 Subject: [PATCH 342/851] Update package.xml (#150) --- sensing_launch/package.xml | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/sensing_launch/package.xml b/sensing_launch/package.xml index b5012e35ed..538895f408 100644 --- a/sensing_launch/package.xml +++ b/sensing_launch/package.xml @@ -9,7 +9,10 @@ Apache License 2.0 ament_cmake_auto - + aip_x1_launch + aip_x2_launch + aip_xx1_launch + common_sensor_launch ament_lint_auto autoware_lint_common From dfb04530b3235bc2a24aa2fc4a35499de9e959b7 Mon Sep 17 00:00:00 2001 From: Taichi Higashide Date: Tue, 7 Dec 2021 13:34:20 +0900 Subject: [PATCH 343/851] change elevation_map_parameters location (#151) --- .../ground_segmentation/elevation_map_parameters.yaml | 0 .../ground_segmentation/ground_segmentation.launch.py | 2 +- 2 files changed, 1 insertion(+), 1 deletion(-) rename perception_launch/config/{object_segmentation => obstacle_segmentation}/ground_segmentation/elevation_map_parameters.yaml (100%) diff --git a/perception_launch/config/object_segmentation/ground_segmentation/elevation_map_parameters.yaml b/perception_launch/config/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml similarity index 100% rename from perception_launch/config/object_segmentation/ground_segmentation/elevation_map_parameters.yaml rename to perception_launch/config/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 9c4b1387ed..fdeda09b26 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -184,7 +184,7 @@ def create_elevation_map_filter_pipeline(ground_segmentation_param): [ FindPackageShare("perception_launch"), "config", - "object_segmentation", + "obstacle_segmentation", "ground_segmentation", "elevation_map_parameters.yaml", ] From ed0193a18b6dcdb9e89fd95da54a22220fec8fb0 Mon Sep 17 00:00:00 2001 From: Taichi Higashide Date: Wed, 8 Dec 2021 15:16:10 +0900 Subject: [PATCH 344/851] refactor ground segmentation launch (#153) --- .../ground_segmentation.param.yaml | 5 +- .../ground_segmentation.launch.py | 840 ++++++++++-------- .../launch/perception.launch.xml | 2 +- 3 files changed, 449 insertions(+), 398 deletions(-) diff --git a/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml b/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml index 67affead0e..33addb108d 100644 --- a/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml +++ b/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml @@ -1,8 +1,9 @@ /**: ros__parameters: additional_lidars: [] - use_ransac_pipeline: False - use_compare_map_pipeline: False + ransac_input_topics: [] + use_single_frame_filter: False + use_time_series_filter: True common_crop_box_filter: parameters: diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index fdeda09b26..8ef6746e09 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -29,418 +29,468 @@ import yaml -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 create_additional_pipeline(vehicle_info, lidar_name, ground_segmentation_param): - crop_box_filter_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", - name=f"{lidar_name}_crop_box_filter", - remappings=[ - ("input", f"/sensing/lidar/{lidar_name}/outlier_filtered/pointcloud"), - ("output", f"{lidar_name}/measurement_range_cropped/pointcloud"), - ], - parameters=[ - { - "input_frame": LaunchConfiguration("base_frame"), - "output_frame": LaunchConfiguration("base_frame"), - "min_z": vehicle_info["min_height_offset"], - "max_z": vehicle_info["max_height_offset"], - }, - ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"], - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - ground_filter_component = ComposableNode( - package="ground_segmentation", - plugin=ground_segmentation_param[f"{lidar_name}_ground_filter"]["plugin"], - name=f"{lidar_name}_ground_filter", - remappings=[ - ("input", f"{lidar_name}/measurement_range_cropped/pointcloud"), - ("output", f"{lidar_name}/no_ground/pointcloud"), - ], - parameters=[ground_segmentation_param[f"{lidar_name}_ground_filter"]["parameters"]], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - return [crop_box_filter_component, ground_filter_component] - - -def create_ransac_pipeline(ground_segmentation_param): - livox_concat_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", - name="livox_concatenate_data", - remappings=[("output", "livox_concatenated/pointcloud")], - parameters=[ - { - "input_topics": [ - "/sensing/lidar/front_left/min_range_cropped/pointcloud", - "/sensing/lidar/front_right/min_range_cropped/pointcloud", - "/sensing/lidar/front_center/min_range_cropped/pointcloud", - ], - "output_frame": LaunchConfiguration("base_frame"), - "timeout_sec": 1.0, - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - short_height_obstacle_detection_area_filter_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", - name="short_height_obstacle_detection_area_filter", - remappings=[ - ("input", "livox_concatenated/pointcloud"), - ("output", "short_height_obstacle_detection_area/pointcloud"), - ], - parameters=[ - { - "input_frame": LaunchConfiguration("base_frame"), - "output_frame": LaunchConfiguration("base_frame"), - }, - ground_segmentation_param["short_height_obstacle_detection_area_filter"]["parameters"], - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - vector_map_filter_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::Lanelet2MapFilterComponent", - name="vector_map_filter", - remappings=[ - ("input/pointcloud", "short_height_obstacle_detection_area/pointcloud"), - ("input/vector_map", "/map/vector_map"), - ("output", "vector_map_filtered/pointcloud"), - ], - parameters=[ - { - "voxel_size_x": 0.25, - "voxel_size_y": 0.25, - } - ], - # cannot use intra process because vector map filter uses transient local. - extra_arguments=[{"use_intra_process_comms": False}], - ) - - ransac_ground_filter_component = ComposableNode( - package="ground_segmentation", - plugin="ground_segmentation::RANSACGroundFilterComponent", - name="ransac_ground_filter", - remappings=[ - ("input", "vector_map_filtered/pointcloud"), - ("output", "short_height/no_ground/pointcloud"), - ], - parameters=[ground_segmentation_param["ransac_ground_filter"]["parameters"]], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - return [ - livox_concat_component, - short_height_obstacle_detection_area_filter_component, - vector_map_filter_component, - ransac_ground_filter_component, - ] - - -def create_elevation_map_filter_pipeline(ground_segmentation_param): - - elevation_map_loader = ComposableNode( - package="elevation_map_loader", - plugin="ElevationMapLoaderNode", - name="elevation_map_loader", - remappings=[ - ("output/elevation_map", "elevation_map"), - ("input/pointcloud_map", "/map/pointcloud_map"), - ("input/vector_map", "/map/vector_map"), - ], - parameters=[ - { - "use_lane_filter": False, - "use_inpaint": True, - "inpaint_radius": 1.0, - "param_file_path": PathJoinSubstitution( - [ - FindPackageShare("perception_launch"), - "config", - "obstacle_segmentation", - "ground_segmentation", - "elevation_map_parameters.yaml", - ] - ), - "elevation_map_directory": PathJoinSubstitution( - [FindPackageShare("elevation_map_loader"), "data", "elevation_maps"] - ), - "use_elevation_map_cloud_publisher": False, - } - ], - extra_arguments=[{"use_intra_process_comms": False}], - ) - - compare_elevation_map_filter_component = ComposableNode( - package="compare_map_segmentation", - plugin="compare_map_segmentation::CompareElevationMapFilterComponent", - name="compare_elevation_map_filter", - remappings=[ - ( - "input", - "no_ground/oneshot/pointcloud" - if bool(ground_segmentation_param["additional_lidars"]) - else "no_ground/pointcloud", - ), - ("output", "map_filtered/pointcloud"), - ("input/elevation_map", "elevation_map"), - ], - parameters=[ - { - "map_frame": "map", - "map_layer_name": "elevation", - "height_diff_thresh": 0.15, - "input_frame": "map", - "output_frame": "base_link", - } - ], - extra_arguments=[{"use_intra_process_comms": False}], # can't use this with transient_local - ) - - downsampling_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", - name="voxel_grid_filter", - remappings=[ - ("input", "map_filtered/pointcloud"), - ("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, - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - voxel_grid_outlier_filter_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::VoxelGridOutlierFilterComponent", - name="voxel_grid_outlier_filter", - remappings=[ - ("input", "voxel_grid_filtered/pointcloud"), - ("output", "/perception/obstacle_segmentation/pointcloud"), - ], - parameters=[ - { - "voxel_size_x": 0.4, - "voxel_size_y": 0.4, - "voxel_size_z": 100.0, - "voxel_points_threshold": 5, - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - return [ - elevation_map_loader, - compare_elevation_map_filter_component, - downsampling_component, - voxel_grid_outlier_filter_component, - ] - - -def launch_setup(context, *args, **kwargs): - - vehicle_info = get_vehicle_info(context) - - ground_segmentation_param_path = os.path.join( - get_package_share_directory("perception_launch"), - "config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml", - ) - with open(ground_segmentation_param_path, "r") as f: - ground_segmentation_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - additional_pipeline_components = [] - if ground_segmentation_param["use_ransac_pipeline"]: - additional_pipeline_components = create_ransac_pipeline(ground_segmentation_param) - else: - for lidar_name in ground_segmentation_param["additional_lidars"]: - additional_pipeline_components.extend( - create_additional_pipeline(vehicle_info, lidar_name, ground_segmentation_param) +class GroundSegmentationPipeline: + def __init__(self, context): + self.context = context + self.vehicle_info = self.get_vehicle_info() + ground_segmentation_param_path = os.path.join( + get_package_share_directory("perception_launch"), + "config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml", + ) + with open(ground_segmentation_param_path, "r") as f: + self.ground_segmentation_param = yaml.safe_load(f)["/**"]["ros__parameters"] + + self.single_frame_obstacle_seg_output = ( + "/perception/obstacle_segmentation/single_frame/pointcloud_raw" + ) + self.output_topic = "/perception/obstacle_segmentation/pointcloud" + self.use_single_frame_filter = self.ground_segmentation_param["use_single_frame_filter"] + self.use_time_series_filter = self.ground_segmentation_param["use_time_series_filter"] + + def get_vehicle_info(self): + path = LaunchConfiguration("vehicle_param_file").perform(self.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(self): + path = LaunchConfiguration("vehicle_mirror_param_file").perform(self.context) + with open(path, "r") as f: + p = yaml.safe_load(f) + return p + + def create_additional_pipeline(self, lidar_name): + components = [] + components.append( + ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::CropBoxFilterComponent", + name=f"{lidar_name}_crop_box_filter", + remappings=[ + ("input", f"/sensing/lidar/{lidar_name}/outlier_filtered/pointcloud"), + ("output", f"{lidar_name}/measurement_range_cropped/pointcloud"), + ], + parameters=[ + { + "input_frame": LaunchConfiguration("base_frame"), + "output_frame": LaunchConfiguration("base_frame"), + "min_z": self.vehicle_info["min_height_offset"], + "max_z": self.vehicle_info["max_height_offset"], + }, + self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"], + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ) + ) + + components.append( + ComposableNode( + package="ground_segmentation", + plugin=self.ground_segmentation_param[f"{lidar_name}_ground_filter"]["plugin"], + name=f"{lidar_name}_ground_filter", + remappings=[ + ("input", f"{lidar_name}/measurement_range_cropped/pointcloud"), + ("output", f"{lidar_name}/no_ground/pointcloud"), + ], + parameters=[ + self.ground_segmentation_param[f"{lidar_name}_ground_filter"]["parameters"] + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ) + ) + + return components + + def create_ransac_pipeline(self): + components = [] + components.append( + ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + name="livox_concatenate_data", + remappings=[("output", "livox_concatenated/pointcloud")], + parameters=[ + { + "input_topics": self.ground_segmentation_param["ransac_input_topics"], + "output_frame": LaunchConfiguration("base_frame"), + "timeout_sec": 1.0, + } + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ) + ) + + components.append( + ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::CropBoxFilterComponent", + name="short_height_obstacle_detection_area_filter", + remappings=[ + ("input", "livox_concatenated/pointcloud"), + ("output", "short_height_obstacle_detection_area/pointcloud"), + ], + parameters=[ + { + "input_frame": LaunchConfiguration("base_frame"), + "output_frame": LaunchConfiguration("base_frame"), + }, + self.ground_segmentation_param["short_height_obstacle_detection_area_filter"][ + "parameters" + ], + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ) + ) + + components.append( + ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::Lanelet2MapFilterComponent", + name="vector_map_filter", + remappings=[ + ("input/pointcloud", "short_height_obstacle_detection_area/pointcloud"), + ("input/vector_map", "/map/vector_map"), + ("output", "vector_map_filtered/pointcloud"), + ], + parameters=[ + { + "voxel_size_x": 0.25, + "voxel_size_y": 0.25, + } + ], + # cannot use intra process because vector map filter uses transient local. + extra_arguments=[{"use_intra_process_comms": False}], + ) + ) + + components.append( + ComposableNode( + package="ground_segmentation", + plugin="ground_segmentation::RANSACGroundFilterComponent", + name="ransac_ground_filter", + remappings=[ + ("input", "vector_map_filtered/pointcloud"), + ("output", "short_height/no_ground/pointcloud"), + ], + parameters=[self.ground_segmentation_param["ransac_ground_filter"]["parameters"]], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ) + ) + + return components + + def create_common_pipeline(self, input_topic, output_topic): + components = [] + components.append( + ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::CropBoxFilterComponent", + name="crop_box_filter", + remappings=[ + ("input", input_topic), + ("output", "measurement_range_cropped/pointcloud"), + ], + parameters=[ + { + "input_frame": LaunchConfiguration("base_frame"), + "output_frame": LaunchConfiguration("base_frame"), + "min_z": self.vehicle_info["min_height_offset"], + "max_z": self.vehicle_info["max_height_offset"], + }, + self.ground_segmentation_param["common_crop_box_filter"]["parameters"], + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ) + ) + + components.append( + ComposableNode( + package="ground_segmentation", + plugin=self.ground_segmentation_param["common_ground_filter"]["plugin"], + name="common_ground_filter", + remappings=[ + ("input", "measurement_range_cropped/pointcloud"), + ("output", output_topic), + ], + parameters=[self.ground_segmentation_param["common_ground_filter"]["parameters"]], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ) + ) + return components + + def create_single_frame_obstacle_segmentation_components(self, input_topic, output_topic): + + additional_lidars = self.ground_segmentation_param["additional_lidars"] + use_ransac = bool(self.ground_segmentation_param["ransac_input_topics"]) + use_additional = bool(additional_lidars) + relay_topic = "no_ground/oneshot/pointcloud" + common_pipeline_output = ( + "no_ground/pointcloud" if use_additional or use_ransac else output_topic + ) + + components = self.create_common_pipeline( + input_topic=input_topic, + output_topic=common_pipeline_output, + ) + + if use_additional: + for lidar_name in additional_lidars: + components.extend(self.create_additional_pipeline(lidar_name)) + components.append( + self.get_additional_lidars_concatenated_component( + input_topics=[common_pipeline_output] + + list(map(lambda x: f"{x}/no_ground/pointcloud"), additional_lidars), + output_topic=relay_topic if use_ransac else output_topic, + ) ) - crop_box_filter_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", - name="crop_box_filter", - remappings=[ - ("input", "/sensing/lidar/concatenated/pointcloud"), - ("output", "measurement_range_cropped/pointcloud"), - ], - parameters=[ - { - "input_frame": LaunchConfiguration("base_frame"), - "output_frame": LaunchConfiguration("base_frame"), - "min_z": vehicle_info["min_height_offset"], - "max_z": vehicle_info["max_height_offset"], - }, - ground_segmentation_param["common_crop_box_filter"]["parameters"], - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) + if use_ransac: + components.extend(self.create_ransac_pipeline()) + components.append( + self.get_single_frame_obstacle_segmentation_concatenated_component( + input_topics=[ + "short_height/no_ground/pointcloud", + relay_topic if use_additional else common_pipeline_output, + ], + output_topic=output_topic, + ) + ) - ground_filter_component = ComposableNode( - package="ground_segmentation", - plugin=ground_segmentation_param["common_ground_filter"]["plugin"], - name="common_ground_filter", - remappings=[ - ("input", "measurement_range_cropped/pointcloud"), - ("output", "no_ground/pointcloud"), - ], - parameters=[ground_segmentation_param["common_ground_filter"]["parameters"]], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) + return components + + @staticmethod + def create_time_series_outlier_filter_components(input_topic, output_topic): + components = [] + components.append( + ComposableNode( + package="occupancy_grid_map_outlier_filter", + plugin="occupancy_grid_map_outlier_filter::OccupancyGridMapOutlierFilterComponent", + name="occupancy_grid_map_outlier_filter", + remappings=[ + ("~/input/occupancy_grid_map", "/perception/occupancy_grid_map/map"), + ("~/input/pointcloud", input_topic), + ("~/output/pointcloud", output_topic), + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ) + ) + + return components + + @staticmethod + def create_single_frame_outlier_filter_components(input_topic, output_topic): + components = [] + components.append( + ComposableNode( + package="elevation_map_loader", + plugin="ElevationMapLoaderNode", + name="elevation_map_loader", + remappings=[ + ("output/elevation_map", "elevation_map"), + ("input/pointcloud_map", "/map/pointcloud_map"), + ("input/vector_map", "/map/vector_map"), + ], + parameters=[ + { + "use_lane_filter": False, + "use_inpaint": True, + "inpaint_radius": 1.0, + "param_file_path": PathJoinSubstitution( + [ + FindPackageShare("perception_launch"), + "config", + "obstacle_segmentation", + "ground_segmentation", + "elevation_map_parameters.yaml", + ] + ), + "elevation_map_directory": PathJoinSubstitution( + [FindPackageShare("elevation_map_loader"), "data", "elevation_maps"] + ), + "use_elevation_map_cloud_publisher": False, + } + ], + extra_arguments=[{"use_intra_process_comms": False}], + ) + ) + + components.append( + ComposableNode( + package="compare_map_segmentation", + plugin="compare_map_segmentation::CompareElevationMapFilterComponent", + name="compare_elevation_map_filter", + remappings=[ + ("input", input_topic), + ("output", "map_filtered/pointcloud"), + ("input/elevation_map", "elevation_map"), + ], + parameters=[ + { + "map_frame": "map", + "map_layer_name": "elevation", + "height_diff_thresh": 0.15, + "input_frame": "map", + "output_frame": "base_link", + } + ], + extra_arguments=[ + {"use_intra_process_comms": False} + ], # can't use this with transient_local + ) + ) + + components.append( + ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", + name="voxel_grid_filter", + remappings=[ + ("input", "map_filtered/pointcloud"), + ("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, + } + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ) + ) + + components.append( + ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::VoxelGridOutlierFilterComponent", + name="voxel_grid_outlier_filter", + remappings=[ + ("input", "voxel_grid_filtered/pointcloud"), + ("output", output_topic), + ], + parameters=[ + { + "voxel_size_x": 0.4, + "voxel_size_y": 0.4, + "voxel_size_z": 100.0, + "voxel_points_threshold": 5, + } + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ) + ) + + return components + + @staticmethod + def get_additional_lidars_concatenated_component(input_topics, output_topic): + + return ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + name="concatenate_data", + remappings=[("output", output_topic)], + parameters=[ + { + "input_topics": input_topics, + "output_frame": LaunchConfiguration("base_frame"), + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + @staticmethod + def get_single_frame_obstacle_segmentation_concatenated_component(input_topics, output_topic): + return ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + name="concatenate_no_ground_data", + remappings=[("output", output_topic)], + parameters=[ + { + "input_topics": input_topics, + "output_frame": LaunchConfiguration("base_frame"), + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) - ground_concat_topics = ["no_ground/pointcloud"] - for lidar_name in ground_segmentation_param["additional_lidars"]: - ground_concat_topics.extend([f"{lidar_name}/no_ground/pointcloud"]) - - concat_data_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", - name="concatenate_data", - remappings=[("output", "no_ground/oneshot/pointcloud")], - parameters=[ - { - "input_topics": ground_concat_topics, - "output_frame": LaunchConfiguration("base_frame"), - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - occupancy_outlier_filter_component = ComposableNode( - package="occupancy_grid_map_outlier_filter", - plugin="occupancy_grid_map_outlier_filter::OccupancyGridMapOutlierFilterComponent", - name="occupancy_grid_map_outlier_filter", - remappings=[ - ("~/input/occupancy_grid_map", "/perception/occupancy_grid_map/map"), - ( - "~/input/pointcloud", - "no_ground/oneshot/pointcloud" - if bool(ground_segmentation_param["additional_lidars"]) - else "no_ground/pointcloud", - ), - ("~/output/pointcloud", "/perception/obstacle_segmentation/pointcloud"), - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], +def launch_setup(context, *args, **kwargs): + pipeline = GroundSegmentationPipeline(context) + + components = [] + components.extend( + pipeline.create_single_frame_obstacle_segmentation_components( + input_topic="/sensing/lidar/concatenated/pointcloud", + output_topic=pipeline.single_frame_obstacle_seg_output, + ) ) - # set container to run all required components in the same process - container = ComposableNodeContainer( + relay_topic = "single_frame/filtered/pointcloud" + if pipeline.use_single_frame_filter: + components.extend( + pipeline.create_single_frame_outlier_filter_components( + input_topic=pipeline.single_frame_obstacle_seg_output, + output_topic=relay_topic + if pipeline.use_time_series_filter + else pipeline.output_topic, + ) + ) + if pipeline.use_time_series_filter: + components.extend( + pipeline.create_time_series_outlier_filter_components( + input_topic=relay_topic + if pipeline.use_single_frame_filter + else pipeline.single_frame_obstacle_seg_output, + output_topic=pipeline.output_topic, + ) + ) + individual_container = ComposableNodeContainer( name=LaunchConfiguration("container_name"), namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[ - crop_box_filter_component, - ground_filter_component, - ], + composable_node_descriptions=components, condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), output="screen", ) - - composable_nodes_loader = LoadComposableNodes( - composable_node_descriptions=[ - crop_box_filter_component, - ground_filter_component, - ], + pointcloud_container_loader = LoadComposableNodes( + composable_node_descriptions=components, target_container=LaunchConfiguration("container_name"), condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), ) - - target_container = ( - container - if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) - else LaunchConfiguration("container_name") - ) - - additional_pipeline_loader = LoadComposableNodes( - composable_node_descriptions=additional_pipeline_components, - target_container=target_container, - condition=IfCondition( - LaunchConfiguration( - "use_additional_pipeline", - default=bool(ground_segmentation_param["additional_lidars"]), - ) - ), - ) - - concat_data_component_loader = LoadComposableNodes( - composable_node_descriptions=[concat_data_component], - target_container=target_container, - condition=IfCondition( - LaunchConfiguration( - "use_additional_pipeline", - default=bool(ground_segmentation_param["additional_lidars"]), - ) - ), - ) - - compare_map_component_loader = LoadComposableNodes( - composable_node_descriptions=create_elevation_map_filter_pipeline( - ground_segmentation_param - ), - target_container=target_container, - condition=IfCondition( - LaunchConfiguration( - "use_compare_map_pipeline", - default=ground_segmentation_param["use_compare_map_pipeline"], - ) - ), - ) - - occupancy_grid_outlier_filter_component_loader = LoadComposableNodes( - composable_node_descriptions=[occupancy_outlier_filter_component], - target_container=target_container, - condition=UnlessCondition( - LaunchConfiguration( - "use_compare_map_pipeline", - default=ground_segmentation_param["use_compare_map_pipeline"], - ) - ), - ) - - return [ - container, - composable_nodes_loader, - additional_pipeline_loader, - compare_map_component_loader, - concat_data_component_loader, - occupancy_grid_outlier_filter_component_loader, - ] + return [individual_container, pointcloud_container_loader] def generate_launch_description(): diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 9949fa84ca..c18c9f9fb4 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -51,7 +51,7 @@ - + From 73157658c34685a496f27e7e2c63b1c2e8aac1f3 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 9 Dec 2021 10:53:06 +0900 Subject: [PATCH 345/851] Fix/update obstacle segmentation namespace (#154) * update topic name * update namespace --- .../ground_segmentation.launch.py | 42 +++++++++++-------- .../launch/perception.launch.xml | 20 ++++----- 2 files changed, 33 insertions(+), 29 deletions(-) diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 8ef6746e09..3428931a9d 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -76,7 +76,7 @@ def create_additional_pipeline(self, lidar_name): name=f"{lidar_name}_crop_box_filter", remappings=[ ("input", f"/sensing/lidar/{lidar_name}/outlier_filtered/pointcloud"), - ("output", f"{lidar_name}/measurement_range_cropped/pointcloud"), + ("output", f"{lidar_name}/range_cropped/pointcloud"), ], parameters=[ { @@ -99,8 +99,8 @@ def create_additional_pipeline(self, lidar_name): plugin=self.ground_segmentation_param[f"{lidar_name}_ground_filter"]["plugin"], name=f"{lidar_name}_ground_filter", remappings=[ - ("input", f"{lidar_name}/measurement_range_cropped/pointcloud"), - ("output", f"{lidar_name}/no_ground/pointcloud"), + ("input", f"{lidar_name}/range_cropped/pointcloud"), + ("output", f"{lidar_name}/pointcloud"), ], parameters=[ self.ground_segmentation_param[f"{lidar_name}_ground_filter"]["parameters"] @@ -119,8 +119,9 @@ def create_ransac_pipeline(self): ComposableNode( package="pointcloud_preprocessor", plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", - name="livox_concatenate_data", - remappings=[("output", "livox_concatenated/pointcloud")], + name="concatenate_data", + namespace="plane_fitting", + remappings=[("output", "concatenated/pointcloud")], parameters=[ { "input_topics": self.ground_segmentation_param["ransac_input_topics"], @@ -139,9 +140,10 @@ def create_ransac_pipeline(self): package="pointcloud_preprocessor", plugin="pointcloud_preprocessor::CropBoxFilterComponent", name="short_height_obstacle_detection_area_filter", + namespace="plane_fitting", remappings=[ - ("input", "livox_concatenated/pointcloud"), - ("output", "short_height_obstacle_detection_area/pointcloud"), + ("input", "concatenated/pointcloud"), + ("output", "detection_area/pointcloud"), ], parameters=[ { @@ -163,8 +165,9 @@ def create_ransac_pipeline(self): package="pointcloud_preprocessor", plugin="pointcloud_preprocessor::Lanelet2MapFilterComponent", name="vector_map_filter", + namespace="plane_fitting", remappings=[ - ("input/pointcloud", "short_height_obstacle_detection_area/pointcloud"), + ("input/pointcloud", "detection_area/pointcloud"), ("input/vector_map", "/map/vector_map"), ("output", "vector_map_filtered/pointcloud"), ], @@ -184,9 +187,10 @@ def create_ransac_pipeline(self): package="ground_segmentation", plugin="ground_segmentation::RANSACGroundFilterComponent", name="ransac_ground_filter", + namespace="plane_fitting", remappings=[ ("input", "vector_map_filtered/pointcloud"), - ("output", "short_height/no_ground/pointcloud"), + ("output", "pointcloud"), ], parameters=[self.ground_segmentation_param["ransac_ground_filter"]["parameters"]], extra_arguments=[ @@ -206,7 +210,7 @@ def create_common_pipeline(self, input_topic, output_topic): name="crop_box_filter", remappings=[ ("input", input_topic), - ("output", "measurement_range_cropped/pointcloud"), + ("output", "range_cropped/pointcloud"), ], parameters=[ { @@ -229,7 +233,7 @@ def create_common_pipeline(self, input_topic, output_topic): plugin=self.ground_segmentation_param["common_ground_filter"]["plugin"], name="common_ground_filter", remappings=[ - ("input", "measurement_range_cropped/pointcloud"), + ("input", "range_cropped/pointcloud"), ("output", output_topic), ], parameters=[self.ground_segmentation_param["common_ground_filter"]["parameters"]], @@ -245,9 +249,9 @@ def create_single_frame_obstacle_segmentation_components(self, input_topic, outp additional_lidars = self.ground_segmentation_param["additional_lidars"] use_ransac = bool(self.ground_segmentation_param["ransac_input_topics"]) use_additional = bool(additional_lidars) - relay_topic = "no_ground/oneshot/pointcloud" + relay_topic = "all_lidars/pointcloud" common_pipeline_output = ( - "no_ground/pointcloud" if use_additional or use_ransac else output_topic + "single_frame/pointcloud" if use_additional or use_ransac else output_topic ) components = self.create_common_pipeline( @@ -261,7 +265,7 @@ def create_single_frame_obstacle_segmentation_components(self, input_topic, outp components.append( self.get_additional_lidars_concatenated_component( input_topics=[common_pipeline_output] - + list(map(lambda x: f"{x}/no_ground/pointcloud"), additional_lidars), + + list(map(lambda x: f"{x}/pointcloud"), additional_lidars), output_topic=relay_topic if use_ransac else output_topic, ) ) @@ -271,7 +275,7 @@ def create_single_frame_obstacle_segmentation_components(self, input_topic, outp components.append( self.get_single_frame_obstacle_segmentation_concatenated_component( input_topics=[ - "short_height/no_ground/pointcloud", + "plane_fitting/pointcloud", relay_topic if use_additional else common_pipeline_output, ], output_topic=output_topic, @@ -309,8 +313,9 @@ def create_single_frame_outlier_filter_components(input_topic, output_topic): package="elevation_map_loader", plugin="ElevationMapLoaderNode", name="elevation_map_loader", + namespace="elevation_map", remappings=[ - ("output/elevation_map", "elevation_map"), + ("output/elevation_map", "map"), ("input/pointcloud_map", "/map/pointcloud_map"), ("input/vector_map", "/map/vector_map"), ], @@ -343,10 +348,11 @@ def create_single_frame_outlier_filter_components(input_topic, output_topic): package="compare_map_segmentation", plugin="compare_map_segmentation::CompareElevationMapFilterComponent", name="compare_elevation_map_filter", + namespace="elevation_map", remappings=[ ("input", input_topic), ("output", "map_filtered/pointcloud"), - ("input/elevation_map", "elevation_map"), + ("input/elevation_map", "map"), ], parameters=[ { @@ -368,6 +374,7 @@ def create_single_frame_outlier_filter_components(input_topic, output_topic): package="pointcloud_preprocessor", plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", name="voxel_grid_filter", + namespace="elevation_map", remappings=[ ("input", "map_filtered/pointcloud"), ("output", "voxel_grid_filtered/pointcloud"), @@ -392,6 +399,7 @@ def create_single_frame_outlier_filter_components(input_topic, output_topic): package="pointcloud_preprocessor", plugin="pointcloud_preprocessor::VoxelGridOutlierFilterComponent", name="voxel_grid_outlier_filter", + namespace="elevation_map", remappings=[ ("input", "voxel_grid_filtered/pointcloud"), ("output", output_topic), diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index c18c9f9fb4..69d301df48 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -33,18 +33,14 @@ - - - - - - - - - - - - + + + + + + + + From c391b4698cb256d651c980fb46d8ea33b42a2aa3 Mon Sep 17 00:00:00 2001 From: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Date: Thu, 16 Dec 2021 15:05:48 +0900 Subject: [PATCH 346/851] Rename some packages references (#157) --- .../include/internal_api_relay.launch.xml | 4 +-- autoware_launch/autoware_launch.drawio.svg | 2 +- autoware_launch/launch/autoware.launch.xml | 4 +-- .../launch/logging_simulator.launch.xml | 4 +-- .../launch/planning_simulator.launch.xml | 4 +-- autoware_launch/package.xml | 4 +-- autoware_launch/rviz/autoware.rviz | 2 +- integration_launch/package.xml | 2 +- system_launch/launch/system.launch.xml | 12 +++---- system_launch/package.xml | 4 +-- system_launch/system_launch.drawio.svg | 34 +++++++++---------- 11 files changed, 38 insertions(+), 38 deletions(-) diff --git a/autoware_api_launch/launch/include/internal_api_relay.launch.xml b/autoware_api_launch/launch/include/internal_api_relay.launch.xml index 46859d0fbd..810e6a566b 100644 --- a/autoware_api_launch/launch/include/internal_api_relay.launch.xml +++ b/autoware_api_launch/launch/include/internal_api_relay.launch.xml @@ -9,12 +9,12 @@ - + - + diff --git a/autoware_launch/autoware_launch.drawio.svg b/autoware_launch/autoware_launch.drawio.svg index 808a956beb..b0f7660b0b 100644 --- a/autoware_launch/autoware_launch.drawio.svg +++ b/autoware_launch/autoware_launch.drawio.svg @@ -1,4 +1,4 @@ -
    autoware.launch.xml

    package: autoware_launch
    autoware.launch.xml...
    launch name

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

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

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

    package: vehicle_launch
    vehicle.launch.xml...
    system.launch.xml

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

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

    package: localization_launch
    localization.launch.xml...
    perception.launch.xml

    package: perception_launch
    perception.launch.xml...
    planning.launch.xml

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

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

    package: control_launch
    awapi_awiv_adapter.launch.xml...
    autoware_web_controller.launch.xml

    package: control_launch
    autoware_web_controller.launch.xml...
    clock_publisher.launch.xml

    package: control_launch
    clock_publisher.launch.xml...
    rviz2

    package: rviz2
    rviz2...
    planning_simulator.xml

    package: autoware_launch
    planning_simulator.xml...
    vehicle_info_launch.py

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

    package: vehicle_launch
    vehicle.launch.xml...
    system.launch.xml

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

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

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

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

    package: control_launch
    awapi_awiv_adapter.launch.xml...
    autoware_web_controller.launch.xml

    package: control_launch
    autoware_web_controller.launch.xml...
    clock_publisher.launch.xml

    package: control_launch
    clock_publisher.launch.xml...
    rviz2

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

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

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

    package: vehicle_launch
    vehicle_description.launch.xml...
    system.launch.xml

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

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

    package: perception_launch
    perception.launch.xml...
    planning.launch.xml

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

    package: control_launch
    control.launch.py...
    autoware_web_controller.launch.xml

    package: control_launch
    autoware_web_controller.launch.xml...
    rviz2

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

    package: sensing_launch
    sensing.launch.xml...
    sensing.launch.xml

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

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

    package: simulator_launch
    simulator.launch.xml...
    simulator.launch.xml

    package: simulator_launch
    simulator.launch.xml...
    Viewer does not support full SVG 1.1
    \ No newline at end of file +
    autoware.launch.xml

    package: autoware_launch
    autoware.launch.xml...
    launch name

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

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

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

    package: vehicle_launch
    vehicle.launch.xml...
    system.launch.xml

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

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

    package: localization_launch
    localization.launch.xml...
    perception.launch.xml

    package: perception_launch
    perception.launch.xml...
    planning.launch.xml

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

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

    package: control_launch
    awapi_awiv_adapter.launch.xml...
    web_controller.launch.xml

    package: control_launch
    web_controller.launch.xml...
    clock_publisher.launch.xml

    package: control_launch
    clock_publisher.launch.xml...
    rviz2

    package: rviz2
    rviz2...
    planning_simulator.xml

    package: autoware_launch
    planning_simulator.xml...
    vehicle_info_launch.py

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

    package: vehicle_launch
    vehicle.launch.xml...
    system.launch.xml

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

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

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

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

    package: control_launch
    awapi_awiv_adapter.launch.xml...
    web_controller.launch.xml

    package: control_launch
    web_controller.launch.xml...
    clock_publisher.launch.xml

    package: control_launch
    clock_publisher.launch.xml...
    rviz2

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

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

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

    package: vehicle_launch
    vehicle_description.launch.xml...
    system.launch.xml

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

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

    package: perception_launch
    perception.launch.xml...
    planning.launch.xml

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

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

    package: control_launch
    web_controller.launch.xml...
    rviz2

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

    package: sensing_launch
    sensing.launch.xml...
    sensing.launch.xml

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

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

    package: simulator_launch
    simulator.launch.xml...
    simulator.launch.xml

    package: simulator_launch
    simulator.launch.xml...
    Viewer does not support full SVG 1.1
    diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 5351d3f9fd..71a7c54eb4 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -12,7 +12,7 @@ - + @@ -84,6 +84,6 @@
    - +
    diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index f23ef0132c..90c2813f98 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -26,7 +26,7 @@ - + @@ -118,7 +118,7 @@ - + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 8738ca011c..94fff17ea4 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -19,7 +19,7 @@ - + @@ -62,7 +62,7 @@ - + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 3816787753..ff6f4dba92 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -10,9 +10,8 @@ ament_cmake_auto autoware_api_launch - autoware_global_parameter_loader - autoware_web_controller control_launch + global_parameter_loader localization_launch map_launch perception_launch @@ -24,6 +23,7 @@ simulator_launch system_launch vehicle_launch + web_controller ament_lint_auto autoware_lint_common diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 9074177c8a..0486b0dbb5 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -16,7 +16,7 @@ Panels: Expanded: ~ Name: Views Splitter Ratio: 0.5 - - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel + - Class: tier4_localization_rviz_plugin/InitialPoseButtonPanel Name: InitialPoseButtonPanel - Class: rviz_common/Time Experimental: false diff --git a/integration_launch/package.xml b/integration_launch/package.xml index 118963ab77..07cf7e3a12 100644 --- a/integration_launch/package.xml +++ b/integration_launch/package.xml @@ -8,7 +8,6 @@ Apache 2 ament_cmake_auto - autoware_web_controller control_launch localization_launch map_launch @@ -20,6 +19,7 @@ sensing_launch system_launch vehicle_launch + web_controller ament_lint_auto autoware_lint_common diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index 8ae917f308..1eb54a4a5c 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -23,16 +23,16 @@ - - - + + + - - - + + + diff --git a/system_launch/package.xml b/system_launch/package.xml index b2150348ef..7f8169ed5e 100644 --- a/system_launch/package.xml +++ b/system_launch/package.xml @@ -10,9 +10,9 @@ ament_cmake_auto - autoware_error_monitor - autoware_state_monitor + ad_service_state_monitor emergency_handler + system_error_monitor system_monitor ament_lint_auto diff --git a/system_launch/system_launch.drawio.svg b/system_launch/system_launch.drawio.svg index b22f005948..bc039dbba8 100644 --- a/system_launch/system_launch.drawio.svg +++ b/system_launch/system_launch.drawio.svg @@ -200,11 +200,11 @@
    - autoware_state_monitor.launch.xml + ad_service_state_monitor.launch.xml

    - package: autoware_state_monitor + package: ad_service_state_monitor

    @@ -212,7 +212,7 @@
    args: config_file = - autoware_state_monitor.param.yaml + ad_service_state_monitor.param.yaml
    @@ -220,7 +220,7 @@
    - autoware_state_monitor.launch.xml... + ad_service_state_monitor.launch.xml... @@ -231,11 +231,11 @@
    - autoware_state_monitor.launch.xml + ad_service_state_monitor.launch.xml

    - package: autoware_state_monitor + package: ad_service_state_monitor

    @@ -243,7 +243,7 @@
    args: config_file = - autoware_state_monitor.planning_simulation.param.yaml + ad_service_state_monitor.planning_simulation.param.yaml
    @@ -251,7 +251,7 @@
    - autoware_state_monitor.launch.xml... + ad_service_state_monitor.launch.xml... @@ -317,11 +317,11 @@
    - autoware_error_monitor.launch.xml + system_error_monitor.launch.xml

    - package: autoware_error_monitor + package: system_error_monitor

    @@ -329,7 +329,7 @@
    args: config_file = - autoware_error_monitor.param.yaml + system_error_monitor.param.yaml
    @@ -337,7 +337,7 @@
    - autoware_error_monitor.launch.xml... + system_error_monitor.launch.xml... @@ -348,11 +348,11 @@
    - autoware_error_monitor.launch.xml + system_error_monitor.launch.xml

    - package: autoware_error_monitor + package: system_error_monitor

    @@ -360,7 +360,7 @@
    args: config_file = - autoware_error_monitor.planning_simulation.param.yaml + system_error_monitor.planning_simulation.param.yaml
    @@ -368,7 +368,7 @@
    - autoware_error_monitor.launch.xml... + system_error_monitor.launch.xml... @@ -405,4 +405,4 @@ - \ No newline at end of file + From 19f1496c6864712ef6ae231d8b02ebd2465f35dd Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Thu, 16 Dec 2021 16:27:08 +0900 Subject: [PATCH 347/851] Fix/topic type (#158) --- .../lane_driving/behavior_planning/behavior_planning.launch.py | 2 +- .../lane_driving/motion_planning/motion_planning.launch.py | 2 +- .../lane_driving/motion_planning/motion_planning.launch.xml | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 1ff96c2244..28971c3842 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -356,7 +356,7 @@ def generate_launch_description(): "pub", "/planning/scenario_planning/lane_driving/behavior_planning/" "behavior_path_planner/path_change_approval", - "autoware_planning_msgs/msg/Approval", + "tier4_planning_msgs/msg/Approval", "{approval: true}", "-r", "10", diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index 036ae246f3..58b6859194 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -114,7 +114,7 @@ def generate_launch_description(): { "input_topic": "obstacle_avoidance_planner/trajectory", "output_topic": "surround_obstacle_checker/trajectory", - "type": "autoware_planning_msgs/msg/Trajectory", + "type": "autoware_auto_planning_msgs/msg/Trajectory", } ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], 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 036b9bcc9f..0ace2bbcc6 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 @@ -29,7 +29,7 @@ - + From 8a8e8002125b0e1cddb023caec4e947a721e30d7 Mon Sep 17 00:00:00 2001 From: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Date: Fri, 17 Dec 2021 16:23:09 +0900 Subject: [PATCH 348/851] fix namespace autoware_planning_msgs -> tier4_planning_msgs (#159) --- .../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 2b9f7d91e7..eaf8370d59 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 @@ -3,7 +3,7 @@ + tier4_planning_msgs/msg/Approval 'approval: true' -r 10"/> From b64106326ae8afa6c8e96fddca25615c137d11ef Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 20 Dec 2021 11:29:42 +0900 Subject: [PATCH 349/851] fix: perception launcher syntax error (#160) --- .../ground_segmentation/ground_segmentation.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 3428931a9d..0d790b8d16 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -265,7 +265,7 @@ def create_single_frame_obstacle_segmentation_components(self, input_topic, outp components.append( self.get_additional_lidars_concatenated_component( input_topics=[common_pipeline_output] - + list(map(lambda x: f"{x}/pointcloud"), additional_lidars), + + list(map(lambda x: f"{x}/pointcloud", additional_lidars)), output_topic=relay_topic if use_ransac else output_topic, ) ) From 94cdbe479838dd83dfe70d41d9bc15ce934b8f03 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 23 Dec 2021 14:57:56 +0900 Subject: [PATCH 350/851] fix simple psim vehicle model param path (#161) --- simulator_launch/launch/simulator.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index 82a9ec8d5d..7fe691ff18 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -29,7 +29,7 @@ - + From 5233b9dc8c188c05446cff31c68e507aa116b982 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Wed, 19 Jan 2022 14:59:06 +0900 Subject: [PATCH 351/851] update parameter (#169) --- .../trajectory_follower/lateral_controller.param.yaml | 4 ++-- .../longitudinal_controller.param.yaml | 10 +++++----- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/control_launch/config/trajectory_follower/lateral_controller.param.yaml b/control_launch/config/trajectory_follower/lateral_controller.param.yaml index d2928e02dd..910aac218e 100644 --- a/control_launch/config/trajectory_follower/lateral_controller.param.yaml +++ b/control_launch/config/trajectory_follower/lateral_controller.param.yaml @@ -44,8 +44,8 @@ # -- 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.1 # steering dynamics time constant (1d approximation) [s] - steer_lim_deg: 20.0 # steering angle limit [deg] + vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approximation) [s] + steer_lim_deg: 40.0 # steering angle limit [deg] 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] diff --git a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml index abcd4458f0..38414ce96b 100644 --- a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml +++ b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml @@ -5,17 +5,17 @@ enable_smooth_stop: true enable_overshoot_emergency: true - enable_slope_compensation: false + enable_slope_compensation: true # state transition drive_state_stop_dist: 0.5 drive_state_offset_stop_dist: 1.0 - stopping_state_stop_dist: 0.49 - stopped_state_entry_vel: 0.1 + stopping_state_stop_dist: 0.5 + stopped_state_entry_vel: 0.01 stopped_state_entry_acc: 0.1 emergency_state_overshoot_stop_dist: 1.5 emergency_state_traj_trans_dev: 3.0 - emergency_state_traj_rot_dev: 0.7 + emergency_state_traj_rot_dev: 0.7854 # drive state kp: 1.0 @@ -36,7 +36,7 @@ # smooth stop state smooth_stop_max_strong_acc: -0.5 - smooth_stop_min_strong_acc: -1.0 + smooth_stop_min_strong_acc: -0.8 smooth_stop_weak_acc: -0.3 smooth_stop_weak_stop_acc: -0.8 smooth_stop_strong_stop_acc: -3.4 From 2dda1c7f2c75da9658df7864549ef5314a9ab09b Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Fri, 21 Jan 2022 15:04:07 +0900 Subject: [PATCH 352/851] Port pure pursuit (#166) * Fix control.launch.py * Apply pre-commit * Fix control.launch.py * Change debug topic name in rviz setting --- autoware_launch/rviz/autoware.rviz | 2 +- control_launch/launch/control.launch.py | 89 ++++++++++++++++++------- 2 files changed, 67 insertions(+), 24 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 0486b0dbb5..d899c433b8 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1421,7 +1421,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /control/trajectory_follower/pure_pursuit/debug/markers + Value: /control/trajectory_follower/pure_pursuit_node_exe/debug/markers Value: false Enabled: true Name: Control diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index d7487d8298..5b3a4fdd9b 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -19,6 +19,7 @@ from launch.actions import OpaqueFunction from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition +from launch.conditions import LaunchConfigurationEquals from launch.conditions import UnlessCondition from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration @@ -31,9 +32,21 @@ def launch_setup(context, *args, **kwargs): - lat_controller_param_path = LaunchConfiguration("lat_controller_param_path").perform(context) - with open(lat_controller_param_path, "r") as f: - lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] + lateral_controller_mode = LaunchConfiguration("lateral_controller_mode").perform(context) + if lateral_controller_mode == "mpc_follower": + lat_controller_param_path = ( + FindPackageShare("control_launch").perform(context) + + "/config/trajectory_follower/lateral_controller.param.yaml" + ) + with open(lat_controller_param_path, "r") as f: + lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] + elif lateral_controller_mode == "pure_pursuit": + lat_controller_param_path = ( + FindPackageShare("control_launch").perform(context) + + "/config/pure_pursuit/pure_pursuit.param.yaml" + ) + with open(lat_controller_param_path, "r") as f: + lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] lon_controller_param_path = LaunchConfiguration("lon_controller_param_path").perform(context) with open(lon_controller_param_path, "r") as f: lon_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] @@ -53,7 +66,7 @@ def launch_setup(context, *args, **kwargs): lane_departure_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] # lateral controller - lat_controller_component = ComposableNode( + mpc_follower_component = ComposableNode( package="trajectory_follower_nodes", plugin="autoware::motion::control::trajectory_follower_nodes::LateralController", name="lateral_controller_node_exe", @@ -71,6 +84,21 @@ def launch_setup(context, *args, **kwargs): ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + pure_pursuit_component = ComposableNode( + package="pure_pursuit", + plugin="pure_pursuit::PurePursuitNode", + name="pure_pursuit_node_exe", + namespace="trajectory_follower", + remappings=[ + ("input/reference_trajectory", "/planning/scenario_planning/trajectory"), + ("input/current_odometry", "/localization/kinematic_state"), + ("output/control_raw", "lateral/control_cmd"), + ], + parameters=[ + lat_controller_param, + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) # longitudinal controller lon_controller_component = ComposableNode( @@ -217,7 +245,7 @@ def launch_setup(context, *args, **kwargs): ) # set container to run all required components in the same process - container = ComposableNodeContainer( + mpc_follower_container = ComposableNodeContainer( name="control_container", namespace="", package="rclcpp_components", @@ -229,22 +257,43 @@ def launch_setup(context, *args, **kwargs): shift_decider_component, vehicle_cmd_gate_component, ], + condition=LaunchConfigurationEquals("lateral_controller_mode", "mpc_follower"), + ) + pure_pursuit_container = ComposableNodeContainer( + name="control_container", + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=[ + lon_controller_component, + latlon_muxer_component, + shift_decider_component, + vehicle_cmd_gate_component, + ], + condition=LaunchConfigurationEquals("lateral_controller_mode", "pure_pursuit"), ) # lateral controller is separated since it may be another controller (e.g. pure pursuit) - lat_controller_loader = LoadComposableNodes( - composable_node_descriptions=[lat_controller_component], - target_container=container, - # condition=LaunchConfigurationEquals("lateral_controller_mode", "mpc"), + mpc_follower_loader = LoadComposableNodes( + composable_node_descriptions=[mpc_follower_component], + target_container=mpc_follower_container, + condition=LaunchConfigurationEquals("lateral_controller_mode", "mpc_follower"), + ) + pure_pursuit_loader = LoadComposableNodes( + composable_node_descriptions=[pure_pursuit_component], + target_container=pure_pursuit_container, + condition=LaunchConfigurationEquals("lateral_controller_mode", "pure_pursuit"), ) group = GroupAction( [ PushRosNamespace("control"), - container, + mpc_follower_container, + pure_pursuit_container, external_cmd_selector_loader, external_cmd_converter_loader, - lat_controller_loader, + mpc_follower_loader, + pure_pursuit_loader, ] ) @@ -259,20 +308,14 @@ def add_launch_arg(name: str, default_value=None, description=None): DeclareLaunchArgument(name, default_value=default_value, description=description) ) - # add_launch_arg( - # "lateral_controller_mode", - # "mpc_follower", - # "lateral controller mode: `mpc_follower` or `pure_pursuit`", - # ) - + # lateral controller mode add_launch_arg( - "lat_controller_param_path", - [ - FindPackageShare("control_launch"), - "/config/trajectory_follower/lateral_controller.param.yaml", - ], - "path to the parameter file of lateral controller", + "lateral_controller_mode", + "mpc_follower", + "lateral controller mode: `mpc_follower` or `pure_pursuit`", ) + + # parameter file path add_launch_arg( "lon_controller_param_path", [ From 3edf482f4d053481abdac1a5400ad2a289b4b2d7 Mon Sep 17 00:00:00 2001 From: YamatoAndo Date: Sun, 23 Jan 2022 15:30:39 +0900 Subject: [PATCH 353/851] fix typo in localization util.launch.py (#168) --- localization_launch/launch/util/util.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/localization_launch/launch/util/util.launch.py b/localization_launch/launch/util/util.launch.py index b6f66fa19e..abcd824b7a 100644 --- a/localization_launch/launch/util/util.launch.py +++ b/localization_launch/launch/util/util.launch.py @@ -55,7 +55,7 @@ def load_composable_node_param(param_path): ) random_downsample_component = ComposableNode( package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", + plugin="pointcloud_preprocessor::RandomDownsampleFilterComponent", name="random_downsample_filter", remappings=[ ("input", LaunchConfiguration("output_voxel_grid_downsample_sensor_points_topic")), From 487097fd2f55a8931307c76ef73bd6058264da5b Mon Sep 17 00:00:00 2001 From: YamatoAndo Date: Mon, 24 Jan 2022 17:38:27 +0900 Subject: [PATCH 354/851] Feature/add covarinace param (#170) * add covariance param * add description --- .../config/ndt_scan_matcher.param.yaml | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/localization_launch/config/ndt_scan_matcher.param.yaml b/localization_launch/config/ndt_scan_matcher.param.yaml index 0448d1fc63..d04b872f14 100644 --- a/localization_launch/config/ndt_scan_matcher.param.yaml +++ b/localization_launch/config/ndt_scan_matcher.param.yaml @@ -32,3 +32,14 @@ # Number of threads used for parallel computing omp_num_threads: 4 + + # The covariance of output pose + output_pose_covariance: + [ + 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.000625, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.000625, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.000625, + ] From d9b8333fc38858f9fb7b429a17d67b4815c2236d Mon Sep 17 00:00:00 2001 From: YamatoAndo Date: Wed, 26 Jan 2022 00:27:06 +0900 Subject: [PATCH 355/851] remove unused param (#172) --- .../launch/pose_estimator/pose_estimator.launch.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml index c3f35464e4..f27899050c 100644 --- a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml +++ b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml @@ -9,7 +9,6 @@ - From 320c3a48a63d4629c7febb582de78a391f4104db Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Thu, 27 Jan 2022 15:30:10 +0900 Subject: [PATCH 356/851] Bump streetsidesoftware/cspell-action from 1.3.4 to v1 (#174) * Bump streetsidesoftware/cspell-action from 1.3.4 to 1.5.0 Bumps [streetsidesoftware/cspell-action](https://github.com/streetsidesoftware/cspell-action) from 1.3.4 to 1.5.0. - [Release notes](https://github.com/streetsidesoftware/cspell-action/releases) - [Changelog](https://github.com/streetsidesoftware/cspell-action/blob/main/CHANGELOG.md) - [Commits](https://github.com/streetsidesoftware/cspell-action/compare/v1.3.4...v1.5.0) --- updated-dependencies: - dependency-name: streetsidesoftware/cspell-action dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] * Update spell_check_pr.yml Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .github/workflows/spell_check_pr.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/spell_check_pr.yml b/.github/workflows/spell_check_pr.yml index f3ae13deea..5b37a85b92 100644 --- a/.github/workflows/spell_check_pr.yml +++ b/.github/workflows/spell_check_pr.yml @@ -16,6 +16,6 @@ jobs: --output .github/workflows/.cspell.json \ https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json - - uses: streetsidesoftware/cspell-action@v1.3.4 + - uses: streetsidesoftware/cspell-action@v1 with: config: ".github/workflows/.cspell.json" From 6a578d9294ce81979f709738fe823b1709c05e35 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Fri, 28 Jan 2022 15:27:42 +0900 Subject: [PATCH 357/851] fix: fix hdd_monitor param (#173) --- system_launch/config/system_monitor/hdd_monitor.param.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/system_launch/config/system_monitor/hdd_monitor.param.yaml b/system_launch/config/system_monitor/hdd_monitor.param.yaml index bf687ae848..2b9bde71ea 100644 --- a/system_launch/config/system_monitor/hdd_monitor.param.yaml +++ b/system_launch/config/system_monitor/hdd_monitor.param.yaml @@ -7,5 +7,5 @@ name: /dev/sda temp_warn: 55.0 temp_error: 70.0 - usage_warn: 0.95 - usage_error: 0.99 + free_warn: 5120 # MB(8hour) + free_error: 100 # MB(last 1 minute) From 8cf14b5023e504036330bc0d3f25c92ffdd840ae Mon Sep 17 00:00:00 2001 From: yabuta Date: Mon, 31 Jan 2022 18:21:52 +0900 Subject: [PATCH 358/851] add rosbridge launch (#175) * add rosbridge launch * fix TODO document add link to pull request Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * fix double-byte character Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- autoware_api_launch/launch/autoware_api.launch.xml | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/autoware_api_launch/launch/autoware_api.launch.xml b/autoware_api_launch/launch/autoware_api.launch.xml index 9e1baf93e5..c3562857fe 100644 --- a/autoware_api_launch/launch/autoware_api.launch.xml +++ b/autoware_api_launch/launch/autoware_api.launch.xml @@ -1,5 +1,7 @@ + + @@ -19,4 +21,10 @@ + + + + + + From 85dba3fff0dc03cb7231d2cad46e9723acb71e03 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-bot[bot]" <98652886+tier4-autoware-bot[bot]@users.noreply.github.com> Date: Mon, 31 Jan 2022 19:00:43 +0900 Subject: [PATCH 359/851] chore: sync files (#177) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .clang-format | 43 +++++++++++++ .github/dependabot.yaml | 7 ++ .github/workflows/automatic-rebase.yaml | 29 +++++++++ .github/workflows/build-and-test-pr.yaml | 68 ++++++++++++++++++++ .github/workflows/build-and-test.yaml | 37 +++++++++++ .github/workflows/pre-commit-optional.yaml | 16 +++++ .github/workflows/pre-commit.yaml | 13 ++-- .github/workflows/semantic-pull-request.yaml | 12 ++++ .github/workflows/spell-check.yaml | 16 +++++ .markdown-link-check.json | 10 +++ .markdownlint.yaml | 1 + .pre-commit-config-optional.yaml | 6 ++ .yamllint.yaml | 20 ++++++ CPPLINT.cfg | 13 ++++ 14 files changed, 282 insertions(+), 9 deletions(-) create mode 100644 .clang-format create mode 100644 .github/dependabot.yaml create mode 100644 .github/workflows/automatic-rebase.yaml create mode 100644 .github/workflows/build-and-test-pr.yaml create mode 100644 .github/workflows/build-and-test.yaml create mode 100644 .github/workflows/pre-commit-optional.yaml create mode 100644 .github/workflows/semantic-pull-request.yaml create mode 100644 .github/workflows/spell-check.yaml create mode 100644 .markdown-link-check.json create mode 100644 .pre-commit-config-optional.yaml create mode 100644 .yamllint.yaml create mode 100644 CPPLINT.cfg diff --git a/.clang-format b/.clang-format new file mode 100644 index 0000000000..7762ec9dfb --- /dev/null +++ b/.clang-format @@ -0,0 +1,43 @@ +# Modified from https://github.com/ament/ament_lint/blob/master/ament_clang_format/ament_clang_format/configuration/.clang-format +Language: Cpp +BasedOnStyle: Google + +AccessModifierOffset: -2 +AlignAfterOpenBracket: AlwaysBreak +BraceWrapping: + AfterClass: true + AfterFunction: true + AfterNamespace: true + AfterStruct: true +BreakBeforeBraces: Custom +ColumnLimit: 100 +ConstructorInitializerIndentWidth: 0 +ContinuationIndentWidth: 2 +DerivePointerAlignment: false +PointerAlignment: Middle +ReflowComments: true +IncludeCategories: + # C++ system headers + - Regex: <[a-z_]*> + Priority: 6 + CaseSensitive: true + # C system headers + - Regex: <.*\.h> + Priority: 5 + CaseSensitive: true + # Boost headers + - Regex: boost/.* + Priority: 4 + CaseSensitive: true + # Message headers + - Regex: .*_msgs/.* + Priority: 3 + CaseSensitive: true + # Other Package headers + - Regex: <.*> + Priority: 2 + CaseSensitive: true + # Local package headers + - Regex: '".*"' + Priority: 1 + CaseSensitive: true diff --git a/.github/dependabot.yaml b/.github/dependabot.yaml new file mode 100644 index 0000000000..9a2fbd7542 --- /dev/null +++ b/.github/dependabot.yaml @@ -0,0 +1,7 @@ +version: 2 +updates: + - package-ecosystem: github-actions + directory: / + schedule: + interval: daily + open-pull-requests-limit: 1 diff --git a/.github/workflows/automatic-rebase.yaml b/.github/workflows/automatic-rebase.yaml new file mode 100644 index 0000000000..8f6dc2b300 --- /dev/null +++ b/.github/workflows/automatic-rebase.yaml @@ -0,0 +1,29 @@ +name: automatic-rebase + +on: + issue_comment: + types: + - created + +jobs: + automatic-rebase: + if: ${{ github.event.issue.pull_request != '' && contains(github.event.comment.body, '/rebase') }} + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Check out repository + uses: actions/checkout@v2 + with: + token: ${{ steps.generate-token.outputs.token }} + fetch-depth: 0 + + - name: Automatic rebase + uses: cirrus-actions/rebase@1.5 + env: + GITHUB_TOKEN: ${{ steps.generate-token.outputs.token }} diff --git a/.github/workflows/build-and-test-pr.yaml b/.github/workflows/build-and-test-pr.yaml new file mode 100644 index 0000000000..c9f5ed6ac7 --- /dev/null +++ b/.github/workflows/build-and-test-pr.yaml @@ -0,0 +1,68 @@ +name: build-and-test-pr + +on: + pull_request: + +jobs: + build-and-test: + runs-on: ubuntu-latest + container: ros:galactic + steps: + - name: Cancel previous runs + uses: styfle/cancel-workflow-action@0.9.1 + + - name: Check out repository + uses: actions/checkout@v2 + with: + fetch-depth: 0 + + - name: Remove exec_depend + uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal + + - name: Register AutonomouStuff repository + uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal + with: + rosdistro: galactic + + - name: Get modified packages + id: get-modified-packages + uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal + + - name: Build and test + if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} + uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal + with: + rosdistro: galactic + target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + build-depends-repos: build_depends.repos + + clang-tidy: + runs-on: ubuntu-latest + container: ros:galactic + needs: build-and-test + steps: + - name: Check out repository + uses: actions/checkout@v2 + with: + fetch-depth: 0 + + - name: Remove exec_depend + uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal + + - name: Register AutonomouStuff repository + uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal + with: + rosdistro: galactic + + - name: Get modified packages + id: get-modified-packages + uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal + + - name: Run clang-tidy + if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} + uses: autowarefoundation/autoware-github-actions/clang-tidy@tier4/proposal + with: + rosdistro: galactic + target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/tier4/proposal/.clang-tidy + build-depends-repos: build_depends.repos diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml new file mode 100644 index 0000000000..a51dc52a57 --- /dev/null +++ b/.github/workflows/build-and-test.yaml @@ -0,0 +1,37 @@ +name: build-and-test + +on: + push: + branches: + - main + - tier4/proposal + schedule: + - cron: 0 19 * * * # run at 4 AM JST + workflow_dispatch: + +jobs: + build-and-test: + runs-on: ubuntu-latest + container: ros:galactic + steps: + - name: Check out repository + uses: actions/checkout@v2 + + - name: Remove exec_depend + uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal + + - name: Register AutonomouStuff repository + uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal + with: + rosdistro: galactic + + - name: Get self packages + id: get-self-packages + uses: autowarefoundation/autoware-github-actions/get-self-packages@tier4/proposal + + - name: Build and test + uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal + with: + rosdistro: galactic + target-packages: ${{ steps.get-self-packages.outputs.self-packages }} + build-depends-repos: build_depends.repos diff --git a/.github/workflows/pre-commit-optional.yaml b/.github/workflows/pre-commit-optional.yaml new file mode 100644 index 0000000000..50b6778a25 --- /dev/null +++ b/.github/workflows/pre-commit-optional.yaml @@ -0,0 +1,16 @@ +name: pre-commit-optional + +on: + pull_request: + +jobs: + pre-commit-optional: + runs-on: ubuntu-latest + steps: + - name: Check out repository + uses: actions/checkout@v2 + + - name: Run pre-commit + uses: autowarefoundation/autoware-github-actions/pre-commit@tier4/proposal + with: + pre-commit-config: .pre-commit-config-optional.yaml diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml index 22e56ca2b6..9eb501a19d 100644 --- a/.github/workflows/pre-commit.yaml +++ b/.github/workflows/pre-commit.yaml @@ -2,20 +2,15 @@ name: pre-commit on: pull_request: - workflow_dispatch: jobs: pre-commit: runs-on: ubuntu-latest - steps: - - name: Checkout repository + - name: Check out repository uses: actions/checkout@v2 - with: - fetch-depth: 0 - - - name: Setup Python - uses: actions/setup-python@v2 - name: Run pre-commit - uses: pre-commit/action@v2.0.3 + uses: autowarefoundation/autoware-github-actions/pre-commit@tier4/proposal + with: + pre-commit-config: .pre-commit-config.yaml diff --git a/.github/workflows/semantic-pull-request.yaml b/.github/workflows/semantic-pull-request.yaml new file mode 100644 index 0000000000..0edf194633 --- /dev/null +++ b/.github/workflows/semantic-pull-request.yaml @@ -0,0 +1,12 @@ +name: semantic-pull-request + +on: + pull_request_target: + types: + - opened + - edited + - synchronize + +jobs: + semantic-pull-request: + uses: autowarefoundation/autoware-github-actions/.github/workflows/semantic-pull-request.yaml@tier4/proposal diff --git a/.github/workflows/spell-check.yaml b/.github/workflows/spell-check.yaml new file mode 100644 index 0000000000..43a75891a3 --- /dev/null +++ b/.github/workflows/spell-check.yaml @@ -0,0 +1,16 @@ +name: spell-check + +on: + pull_request: + +jobs: + spell-check: + runs-on: ubuntu-latest + steps: + - name: Check out repository + uses: actions/checkout@v2 + + - name: Run spell-check + uses: autowarefoundation/autoware-github-actions/spell-check@tier4/proposal + with: + cspell-json-url: https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json diff --git a/.markdown-link-check.json b/.markdown-link-check.json new file mode 100644 index 0000000000..331095d38d --- /dev/null +++ b/.markdown-link-check.json @@ -0,0 +1,10 @@ +{ + "aliveStatusCodes": [200, 206, 403], + "ignorePatterns": [ + { + "pattern": "^http://localhost" + } + ], + "retryOn429": true, + "retryCount": 10 +} diff --git a/.markdownlint.yaml b/.markdownlint.yaml index 605ac41ce9..dbd5b9703d 100644 --- a/.markdownlint.yaml +++ b/.markdownlint.yaml @@ -4,3 +4,4 @@ MD024: siblings_only: true MD033: false MD041: false +MD046: false diff --git a/.pre-commit-config-optional.yaml b/.pre-commit-config-optional.yaml new file mode 100644 index 0000000000..e54ba1fdd5 --- /dev/null +++ b/.pre-commit-config-optional.yaml @@ -0,0 +1,6 @@ +repos: + - repo: https://github.com/tcort/markdown-link-check + rev: v3.9.3 + hooks: + - id: markdown-link-check + args: [--config=.markdown-link-check.json] diff --git a/.yamllint.yaml b/.yamllint.yaml new file mode 100644 index 0000000000..1d4ee33eca --- /dev/null +++ b/.yamllint.yaml @@ -0,0 +1,20 @@ +extends: default + +ignore: | + .clang-tidy + *.param.yaml + +rules: + comments: + level: error + min-spaces-from-content: 1 # To be compatible with C++ and Python + document-start: + level: error + present: false # Don't need document start markers + line-length: disable # Delegate to Prettier + truthy: + level: error + check-keys: false # To allow 'on' of GitHub Actions + quoted-strings: + level: error + required: only-when-needed # To keep consistent style diff --git a/CPPLINT.cfg b/CPPLINT.cfg new file mode 100644 index 0000000000..4dbbe0596b --- /dev/null +++ b/CPPLINT.cfg @@ -0,0 +1,13 @@ +# Modified from https://github.com/ament/ament_lint/blob/ebd524bb9973d5ec1dc48a670ce54f958a5a0243/ament_cpplint/ament_cpplint/main.py#L64-L120 +set noparent +linelength=100 +includeorder=standardcfirst +filter=-build/c++11 # we do allow C++11 +filter=-build/namespaces_literals # we allow using namespace for literals +filter=-runtime/references # we consider passing non-const references to be ok +filter=-whitespace/braces # we wrap open curly braces for namespaces, classes and functions +filter=-whitespace/indent # we don't indent keywords like public, protected and private with one space +filter=-whitespace/parens # we allow closing parenthesis to be on the next line +filter=-whitespace/semicolon # we allow the developer to decide about whitespace after a semicolon +filter=-build/header_guard # TODO(Kenji Miyake): Support ROS-style rule in cpplint or add auto-fix script in pre-commit +filter=-build/include_order # we use the custom include order From 7d3844e0562ab7e0ad6bacdc3f390816140c9cb3 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 1 Feb 2022 10:36:02 +0900 Subject: [PATCH 360/851] ci: update CI settings (#176) * ci(pre-commit): update .pre-commit-config.yaml Signed-off-by: Kenji Miyake * ci: add sync-files.yaml Signed-off-by: Kenji Miyake * chore: remove old workflows Signed-off-by: Kenji Miyake * ci(sync-upstream): update sync-upstream.yaml Signed-off-by: Kenji Miyake * ci(pre-commit): autofix * style: fix for yamllint Signed-off-by: Kenji Miyake Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .github/dependabot.yml | 7 - .github/get_modified_package.sh | 74 +++++------ .github/labeler-develop.yml | 4 - .github/labeler-main.yml | 4 - .github/labeler-rc.yml | 4 - .github/labeler.yml | 2 - .github/sync-files.yaml | 22 ++++ .github/workflows/build_and_test.yml | 68 ---------- .github/workflows/build_and_test_pr.yml | 69 ---------- .github/workflows/labeler.yml | 29 ----- .github/workflows/spell_check_all.yml | 39 ------ .github/workflows/spell_check_pr.yml | 21 --- .github/workflows/sync-files.yaml | 22 ++++ .github/workflows/sync-main-for-develop.yml | 66 ---------- .github/workflows/sync-public-develop.yaml | 40 ------ .github/workflows/sync-public.yaml | 40 ------ .github/workflows/sync-rc.yml | 121 ------------------ .github/workflows/sync-upstream-develop.yml | 77 ----------- .github/workflows/sync-upstream.yml | 75 ++--------- .github/workflows/update-pre-commit.yml | 42 ------ .pre-commit-config.yaml | 78 ++++++----- .../elevation_map_parameters.yaml | 2 +- 22 files changed, 138 insertions(+), 768 deletions(-) delete mode 100644 .github/dependabot.yml delete mode 100644 .github/labeler-develop.yml delete mode 100644 .github/labeler-main.yml delete mode 100644 .github/labeler-rc.yml delete mode 100644 .github/labeler.yml create mode 100644 .github/sync-files.yaml delete mode 100644 .github/workflows/build_and_test.yml delete mode 100644 .github/workflows/build_and_test_pr.yml delete mode 100644 .github/workflows/labeler.yml delete mode 100644 .github/workflows/spell_check_all.yml delete mode 100644 .github/workflows/spell_check_pr.yml create mode 100644 .github/workflows/sync-files.yaml delete mode 100644 .github/workflows/sync-main-for-develop.yml delete mode 100644 .github/workflows/sync-public-develop.yaml delete mode 100644 .github/workflows/sync-public.yaml delete mode 100644 .github/workflows/sync-rc.yml delete mode 100644 .github/workflows/sync-upstream-develop.yml delete mode 100644 .github/workflows/update-pre-commit.yml diff --git a/.github/dependabot.yml b/.github/dependabot.yml deleted file mode 100644 index b940a74a4c..0000000000 --- a/.github/dependabot.yml +++ /dev/null @@ -1,7 +0,0 @@ -version: 2 -updates: - - package-ecosystem: "github-actions" - directory: "/" - schedule: - interval: "daily" - open-pull-requests-limit: 1 diff --git a/.github/get_modified_package.sh b/.github/get_modified_package.sh index cc99e534a4..7f9cd4b2f1 100755 --- a/.github/get_modified_package.sh +++ b/.github/get_modified_package.sh @@ -10,47 +10,47 @@ ROOT_DIR=$(readlink -f "$SCRIPT_DIR"/../) # Parse arguments args=() while [ "${1:-}" != "" ]; do - case "$1" in + case "$1" in *) - args+=("$1") - ;; - esac - shift + args+=("$1") + ;; + esac + shift done base_branch="${args[0]}" # Check args if [ "$base_branch" = "" ]; then - echo -e "\e[31mPlease input a valid base_branch as the 1st argument.\e[m" - exit 1 + echo -e "\e[31mPlease input a valid base_branch as the 1st argument.\e[m" + exit 1 fi function find_package_dir() { - [ "$1" == "" ] && return 1 - - target_dir=$(dirname "$1") - while true ; do - parent_dir=$(dirname "$target_dir") - - # Exit if no parent found - if [ "$parent_dir" = "$target_dir" ] ; then - return 0 - fi - - # Output package name if package.xml found - if [ -f "$target_dir/package.xml" ] ; then - if [ ! -f "$target_dir/COLCON_IGNORE" ] ; then - echo "$target_dir" - return 0 - fi - fi - - # Move to parent dir - target_dir=$parent_dir - done - - return 1 + [ "$1" == "" ] && return 1 + + target_dir=$(dirname "$1") + while true; do + parent_dir=$(dirname "$target_dir") + + # Exit if no parent found + if [ "$parent_dir" = "$target_dir" ]; then + return 0 + fi + + # Output package name if package.xml found + if [ -f "$target_dir/package.xml" ]; then + if [ ! -f "$target_dir/COLCON_IGNORE" ]; then + echo "$target_dir" + return 0 + fi + fi + + # Move to parent dir + target_dir=$parent_dir + done + + return 1 } # Find modified files from base branch @@ -59,16 +59,16 @@ modified_files=$(git diff --name-only "$base_branch"...HEAD) # Find modified packages modified_package_dirs=() for modified_file in $modified_files; do - modified_package_dir=$(find_package_dir "$ROOT_DIR/$modified_file") + modified_package_dir=$(find_package_dir "$ROOT_DIR/$modified_file") - if [ "$modified_package_dir" != "" ] ; then - modified_package_dirs+=("$modified_package_dir") - fi + if [ "$modified_package_dir" != "" ]; then + modified_package_dirs+=("$modified_package_dir") + fi done # Get package names from paths -if [ "${#modified_package_dirs[@]}" != "0" ] ; then - modified_packages=$(colcon list --names-only --paths "${modified_package_dirs[@]}") +if [ "${#modified_package_dirs[@]}" != "0" ]; then + modified_packages=$(colcon list --names-only --paths "${modified_package_dirs[@]}") fi # Output diff --git a/.github/labeler-develop.yml b/.github/labeler-develop.yml deleted file mode 100644 index 04df147b74..0000000000 --- a/.github/labeler-develop.yml +++ /dev/null @@ -1,4 +0,0 @@ -develop: - - "**" - - "**/.*" - - ".*/**" diff --git a/.github/labeler-main.yml b/.github/labeler-main.yml deleted file mode 100644 index 5a441060d0..0000000000 --- a/.github/labeler-main.yml +++ /dev/null @@ -1,4 +0,0 @@ -main: - - "**" - - "**/.*" - - ".*/**" diff --git a/.github/labeler-rc.yml b/.github/labeler-rc.yml deleted file mode 100644 index 1742be2f7b..0000000000 --- a/.github/labeler-rc.yml +++ /dev/null @@ -1,4 +0,0 @@ -rc: - - "**" - - "**/.*" - - ".*/**" diff --git a/.github/labeler.yml b/.github/labeler.yml deleted file mode 100644 index a8d83b209a..0000000000 --- a/.github/labeler.yml +++ /dev/null @@ -1,2 +0,0 @@ -CI: - - ".github/**" diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml new file mode 100644 index 0000000000..7a2da49689 --- /dev/null +++ b/.github/sync-files.yaml @@ -0,0 +1,22 @@ +- repository: autowarefoundation/autoware + files: + - source: .github/dependabot.yaml + - source: .github/workflows/pre-commit-optional.yaml + - source: .github/workflows/semantic-pull-request.yaml + - source: .github/workflows/spell-check.yaml + - source: .clang-format + - source: .markdown-link-check.json + - source: .markdownlint.yaml + - source: .pre-commit-config-optional.yaml + - source: .prettierignore + - source: .prettierrc + - source: .yamllint.yaml + - source: CPPLINT.cfg + - source: setup.cfg + +- repository: autowarefoundation/autoware_common + files: + - source: .github/workflows/automatic-rebase.yaml + - source: .github/workflows/build-and-test.yaml + - source: .github/workflows/build-and-test-pr.yaml + - source: .github/workflows/pre-commit.yaml diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml deleted file mode 100644 index 16e047639f..0000000000 --- a/.github/workflows/build_and_test.yml +++ /dev/null @@ -1,68 +0,0 @@ -name: Build and test - -on: - schedule: - - cron: "0 19 * * *" # run at 4 AM JST - workflow_dispatch: - -jobs: - build-and-test: - runs-on: ubuntu-latest - strategy: - fail-fast: false - matrix: - branch: - - main - - develop - container: rostooling/setup-ros-docker:ubuntu-focal-ros-galactic-ros-base-latest - - steps: - - name: Checkout repository - uses: actions/checkout@v2 - with: - ref: ${{ matrix.branch }} - - - name: Install pip - run: | - apt-get -y update - apt-get -y install python3-pip - - - name: Search packages in this repository - id: list_packages - run: | - echo ::set-output name=package_list::$(colcon list --names-only) - - - name: Show target packages - run: | - echo "Target packages: ${{ steps.list_packages.outputs.package_list }}" - - - name: Remove exec_depend to avoid unnecessary build - run: | - find . -name package.xml | xargs -I {} sed -i -rz "s|\s*[a-zA-Z_0-9]+\s*\n||g" {} - - - name: Set git config for private repositories - run: | - git config --local --unset-all http.https://github.com/.extraheader || true - git config --global url.https://${{ secrets.REPO_TOKEN }}@github.com.insteadOf 'https://github.com' - - - name: Clone dependency packages - run: | - mkdir dependency_ws - vcs import dependency_ws < build_depends.repos - apt-get -y update - rosdep update - DEBIAN_FRONTEND=noninteractive rosdep install -y --from-paths . --ignore-src --rosdistro galactic - - - name: Build - run: | - . /opt/ros/galactic/setup.sh - colcon build --event-handlers console_cohesion+ \ - --packages-up-to ${{ steps.list_packages.outputs.package_list }} \ - --cmake-args -DCMAKE_BUILD_TYPE=Release - - - name: Run tests - run: | - . /opt/ros/galactic/setup.sh - colcon test --event-handlers console_cohesion+ \ - --packages-select ${{ steps.list_packages.outputs.package_list }} \ - --return-code-on-test-failure diff --git a/.github/workflows/build_and_test_pr.yml b/.github/workflows/build_and_test_pr.yml deleted file mode 100644 index 144bff1611..0000000000 --- a/.github/workflows/build_and_test_pr.yml +++ /dev/null @@ -1,69 +0,0 @@ -name: Build and test for PR - -on: - pull_request: - -jobs: - build-and-test-pr: - runs-on: ubuntu-latest - container: rostooling/setup-ros-docker:ubuntu-focal-ros-galactic-ros-base-latest - - steps: - - name: Cancel previous runs - uses: styfle/cancel-workflow-action@0.9.1 - - - name: Checkout repository - uses: actions/checkout@v2 - with: - # Fetch with depth=0 to calculate modified packages - fetch-depth: 0 - - - name: Install pip - run: | - apt-get -y update - apt-get -y install python3-pip - - - name: Search modified packages - id: list_packages - run: | - ${GITHUB_WORKSPACE}/.github/get_modified_package.sh origin/${{ github.base_ref }} - - - name: Show target packages - run: | - echo "Target packages: ${{ steps.list_packages.outputs.package_list }}" - - - name: Remove exec_depend to avoid unnecessary build - if: ${{ steps.list_packages.outputs.package_list != '' }} - run: | - find . -name package.xml | xargs -I {} sed -i -rz "s|\s*[a-zA-Z_0-9]+\s*\n||g" {} - - - name: Set git config for private repositories - if: ${{ steps.list_packages.outputs.package_list != '' }} - run: | - git config --local --unset-all http.https://github.com/.extraheader || true - git config --global url.https://${{ secrets.REPO_TOKEN }}@github.com.insteadOf 'https://github.com' - - - name: Clone dependency packages - if: ${{ steps.list_packages.outputs.package_list != '' }} - run: | - mkdir dependency_ws - vcs import dependency_ws < build_depends.repos - apt-get -y update - rosdep update - DEBIAN_FRONTEND=noninteractive rosdep install -y --from-paths . --ignore-src --rosdistro galactic - - - name: Build - if: ${{ steps.list_packages.outputs.package_list != '' }} - run: | - . /opt/ros/galactic/setup.sh - colcon build --event-handlers console_cohesion+ \ - --packages-up-to ${{ steps.list_packages.outputs.package_list }} \ - --cmake-args -DCMAKE_BUILD_TYPE=Release - - - name: Run tests - if: ${{ steps.list_packages.outputs.package_list != '' }} - run: | - . /opt/ros/galactic/setup.sh - colcon test --event-handlers console_cohesion+ \ - --packages-select ${{ steps.list_packages.outputs.package_list }} \ - --return-code-on-test-failure diff --git a/.github/workflows/labeler.yml b/.github/workflows/labeler.yml deleted file mode 100644 index 6216cbae52..0000000000 --- a/.github/workflows/labeler.yml +++ /dev/null @@ -1,29 +0,0 @@ -name: Labeler -on: - pull_request: - branches: - - main - - develop - - rc/* - -jobs: - labeler: - runs-on: ubuntu-latest - - steps: - - name: Run labeler - uses: actions/labeler@v3 - with: - configuration-path: .github/labeler.yml - repo-token: "${{ secrets.GITHUB_TOKEN }}" - - - name: Set LABELER_SUFFIX - run: | - branch_name=${GITHUB_BASE_REF#refs/heads/} - echo "LABELER_SUFFIX=${branch_name%/*}" >> $GITHUB_ENV - - - name: Run labeler for branch - uses: actions/labeler@v3 - with: - configuration-path: .github/labeler-${{ env.LABELER_SUFFIX }}.yml - repo-token: "${{ secrets.GITHUB_TOKEN }}" diff --git a/.github/workflows/spell_check_all.yml b/.github/workflows/spell_check_all.yml deleted file mode 100644 index 341bc91e9a..0000000000 --- a/.github/workflows/spell_check_all.yml +++ /dev/null @@ -1,39 +0,0 @@ -name: Check spelling (all files) - -on: - workflow_dispatch: - inputs: - ignore_patterns: - description: "ignore patterns (ex. *.svg|*.osm)" - required: false - -jobs: - spellcheck: - runs-on: ubuntu-latest - steps: - - name: Checkout repository - uses: actions/checkout@v2 - - - name: Prepare node - uses: actions/setup-node@v2 - - - name: Install cspell - run: | - npm install cspell - - - name: Retrieve spell check dictionary - run: | - curl --silent --show-error \ - --output .github/workflows/.cspell.json \ - https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json - - - name: Check spelling - run: | - # The cspell-action might not be able to exclude specific files. - # So use cspell package directly instead. - # How to exclude specific files: - # Ex. "**/!(*.osm|*.svg|CHANGELOG.rst)" - ./node_modules/.bin/cspell \ - --config .github/workflows/.cspell.json \ - "**/!(${{ github.event.inputs.ignore_patterns }})" \ - 2> /dev/null diff --git a/.github/workflows/spell_check_pr.yml b/.github/workflows/spell_check_pr.yml deleted file mode 100644 index 5b37a85b92..0000000000 --- a/.github/workflows/spell_check_pr.yml +++ /dev/null @@ -1,21 +0,0 @@ -name: Check spelling - -on: - pull_request: - -jobs: - spellcheck: - runs-on: ubuntu-latest - steps: - - name: Checkout repository - uses: actions/checkout@v2 - - - name: Retrieve spell check dictionary - run: | - curl --silent --show-error \ - --output .github/workflows/.cspell.json \ - https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json - - - uses: streetsidesoftware/cspell-action@v1 - with: - config: ".github/workflows/.cspell.json" diff --git a/.github/workflows/sync-files.yaml b/.github/workflows/sync-files.yaml new file mode 100644 index 0000000000..0c5b4b04fa --- /dev/null +++ b/.github/workflows/sync-files.yaml @@ -0,0 +1,22 @@ +name: sync-files + +on: + schedule: + - cron: 0 19 * * * # run at 4 AM JST + workflow_dispatch: + +jobs: + sync-files: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-files + uses: autowarefoundation/autoware-github-actions/sync-files@tier4/proposal + with: + token: ${{ steps.generate-token.outputs.token }} diff --git a/.github/workflows/sync-main-for-develop.yml b/.github/workflows/sync-main-for-develop.yml deleted file mode 100644 index ea329bf8a5..0000000000 --- a/.github/workflows/sync-main-for-develop.yml +++ /dev/null @@ -1,66 +0,0 @@ -name: sync main for develop - -on: - schedule: - - cron: "0 19 * * *" # run at 4 AM JST - workflow_dispatch: - -env: - BASE_BRANCH: develop - SYNC_TARGET_BRANCH: main - SYNC_BRANCH: sync-main-for-develop - -jobs: - sync-main-for-develop: - runs-on: ubuntu-20.04 - - steps: - - name: Checkout repository - uses: actions/checkout@v2 - with: - ref: ${{ env.BASE_BRANCH }} - fetch-depth: 0 - - - name: Generate token - uses: tibdex/github-app-token@v1 - id: generate-token - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.APP_PRIVATE_KEY }} - - # To keep the base branch in "create-pull-request", checkout with "BASE_BRANCH" and reset to "SYNC_TARGET_BRANCH" - - name: Reset to sync target branch - run: | - git reset --hard origin/${{ env.SYNC_TARGET_BRANCH }} - - - name: Create PR - id: create_pr - uses: peter-evans/create-pull-request@v3 - with: - token: ${{ steps.generate-token.outputs.token }} - commit-message: sync main for develop - committer: GitHub - author: GitHub - signoff: false - base: ${{ env.BASE_BRANCH }} - branch: ${{ env.SYNC_BRANCH }} - delete-branch: true - title: sync main for develop - body: | - sync main for develop - labels: | - sync-main-for-develop - draft: false - - - name: Check outputs - run: | - echo "Pull Request Number - ${{ steps.create_pr.outputs.pull-request-number }}" - echo "Pull Request URL - ${{ steps.create_pr.outputs.pull-request-url }}" - - - name: Enable Auto-merge - if: steps.create_pr.outputs.pull-request-operation == 'created' - uses: peter-evans/enable-pull-request-automerge@v1 - with: - token: ${{ steps.generate-token.outputs.token }} - pull-request-number: ${{ steps.create_pr.outputs.pull-request-number }} - merge-method: merge diff --git a/.github/workflows/sync-public-develop.yaml b/.github/workflows/sync-public-develop.yaml deleted file mode 100644 index 874b81344c..0000000000 --- a/.github/workflows/sync-public-develop.yaml +++ /dev/null @@ -1,40 +0,0 @@ -name: sync public - -on: - schedule: - - cron: "0 19 * * *" # run at 4 AM JST - workflow_dispatch: - -env: - BASE_BRANCH: develop - SYNC_TARGET_BRANCH: develop - SYNC_TARGET_REPOSITORY: https://github.com/tier4/AutowareArchitectureProposal_launcher.git - -jobs: - sync-public: - runs-on: ubuntu-20.04 - - steps: - - name: Checkout repository - uses: actions/checkout@v2 - with: - ref: ${{ env.BASE_BRANCH }} - fetch-depth: 0 - - - name: Generate token - uses: tibdex/github-app-token@v1 - id: generate-token - with: - app_id: ${{ secrets.PROPOSAL_SYNC_APP_ID }} - private_key: ${{ secrets.PROPOSAL_SYNC_APP_PRIVATE_KEY }} - - - name: Set git config for private repositories - run: | - git config --local --unset-all http.https://github.com/.extraheader || true - git config --global url.https://x-access-token:${{ steps.generate-token.outputs.token }}@github.com.insteadOf 'https://github.com' - - - name: Push to public repository - run: | - git remote add public ${{ env.SYNC_TARGET_REPOSITORY }} - git fetch public - git push public ${{ env.BASE_BRANCH }}:${{ env.SYNC_TARGET_BRANCH }} diff --git a/.github/workflows/sync-public.yaml b/.github/workflows/sync-public.yaml deleted file mode 100644 index 8cc1453bf3..0000000000 --- a/.github/workflows/sync-public.yaml +++ /dev/null @@ -1,40 +0,0 @@ -name: sync public - -on: - schedule: - - cron: "0 19 * * *" # run at 4 AM JST - workflow_dispatch: - -env: - BASE_BRANCH: main - SYNC_TARGET_BRANCH: main - SYNC_TARGET_REPOSITORY: https://github.com/tier4/AutowareArchitectureProposal_launcher.git - -jobs: - sync-public: - runs-on: ubuntu-20.04 - - steps: - - name: Checkout repository - uses: actions/checkout@v2 - with: - ref: ${{ env.BASE_BRANCH }} - fetch-depth: 0 - - - name: Generate token - uses: tibdex/github-app-token@v1 - id: generate-token - with: - app_id: ${{ secrets.PROPOSAL_SYNC_APP_ID }} - private_key: ${{ secrets.PROPOSAL_SYNC_APP_PRIVATE_KEY }} - - - name: Set git config for private repositories - run: | - git config --local --unset-all http.https://github.com/.extraheader || true - git config --global url.https://x-access-token:${{ steps.generate-token.outputs.token }}@github.com.insteadOf 'https://github.com' - - - name: Push to public repository - run: | - git remote add public ${{ env.SYNC_TARGET_REPOSITORY }} - git fetch public - git push public ${{ env.BASE_BRANCH }}:${{ env.SYNC_TARGET_BRANCH }} diff --git a/.github/workflows/sync-rc.yml b/.github/workflows/sync-rc.yml deleted file mode 100644 index 748d8a2be7..0000000000 --- a/.github/workflows/sync-rc.yml +++ /dev/null @@ -1,121 +0,0 @@ -name: sync rc - -on: - pull_request: - branches: - - "rc/*" - types: - - closed - workflow_dispatch: - inputs: - rc_branch: - description: "Target RC branch(e.g. rc/v1.0.0)" - required: true - -jobs: - sync-rc: - runs-on: ubuntu-20.04 - - steps: - - name: Checkout repository - uses: actions/checkout@v2 - with: - fetch-depth: 0 - - - name: Generate token - uses: tibdex/github-app-token@v1 - id: generate-token - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.APP_PRIVATE_KEY }} - - - name: Set SYNC_TARGET_BRANCH for pull_request event - if: github.event_name == 'pull_request' - run: | - echo "SYNC_TARGET_BRANCH=${{ github.base_ref }}" >> $GITHUB_ENV - - - name: Set SYNC_TARGET_BRANCH for workflow_dispatch event - if: github.event_name == 'workflow_dispatch' - run: | - echo "SYNC_TARGET_BRANCH=${{ github.event.inputs.rc_branch }}" >> $GITHUB_ENV - - - name: Set SYNC_BRANCH - run: | - echo ${SYNC_TARGET_BRANCH} | grep -e "^rc/v.*" - echo "SYNC_BRANCH=sync-rc/${SYNC_TARGET_BRANCH#refs/heads/}" >> $GITHUB_ENV - - - name: Judge BASE_BRANCH - run: | - function is_main_base() { - target_branch="$1" - - git rev-parse --quiet --verify origin/develop || return 0 - - main_base=$(git merge-base "${target_branch}" origin/main) - develop_base=$(git merge-base "${target_branch}" origin/develop) - - return $(test "${main_base}" = "${develop_base}") - } - - if is_main_base "origin/${{ env.SYNC_TARGET_BRANCH }}"; then - base_branch=main - else - base_branch=develop - fi - - echo "BASE_BRANCH=${base_branch}" >> $GITHUB_ENV - - - name: Checkout repository - uses: actions/checkout@v2 - with: - ref: ${{ env.BASE_BRANCH }} - fetch-depth: 0 - - # To keep the base branch in "create-pull-request", checkout with "BASE_BRANCH" and reset to "SYNC_TARGET_BRANCH" - - name: Reset to sync target branch - run: | - git reset --hard origin/${{ env.SYNC_TARGET_BRANCH }} - - - name: Set git config - run: | - git config --local user.email "actions@example.com" - git config --local user.name "Github Actions" - - - name: Rebase on the base branch - run: | - for commit in $(git rev-list --left-only "origin/${{ env.BASE_BRANCH }}"...HEAD | tac); do - merge_base=$(git merge-base HEAD "origin/${{ env.BASE_BRANCH }}") - git rebase --onto "$commit" "$merge_base" "${{ env.BASE_BRANCH }}" || git rebase --abort - done - - - name: Create PR - id: create_pr - uses: peter-evans/create-pull-request@v3 - with: - token: ${{ steps.generate-token.outputs.token }} - commit-message: sync rc - committer: GitHub - author: GitHub - signoff: false - base: ${{ env.BASE_BRANCH }} - branch: ${{ env.SYNC_BRANCH }} - delete-branch: true - title: sync rc ${{ env.SYNC_TARGET_BRANCH }} - body: | - sync rc ${{ env.SYNC_TARGET_BRANCH }} - labels: | - sync-rc - draft: false - - - name: Check outputs - run: | - echo "Pull Request Number - ${{ steps.create_pr.outputs.pull-request-number }}" - echo "Pull Request URL - ${{ steps.create_pr.outputs.pull-request-url }}" - - - name: Enable Auto-merge - if: steps.create_pr.outputs.pull-request-operation == 'created' - uses: peter-evans/enable-pull-request-automerge@v1 - with: - token: ${{ steps.generate-token.outputs.token }} - pull-request-number: ${{ steps.create_pr.outputs.pull-request-number }} - merge-method: squash diff --git a/.github/workflows/sync-upstream-develop.yml b/.github/workflows/sync-upstream-develop.yml deleted file mode 100644 index b288a0fb16..0000000000 --- a/.github/workflows/sync-upstream-develop.yml +++ /dev/null @@ -1,77 +0,0 @@ -name: sync upstream develop - -on: - schedule: - - cron: "0 19 * * *" # run at 4 AM JST - workflow_dispatch: - -env: - UPSTREAM_REPO: https://github.com/tier4/autoware_launcher.git - BASE_BRANCH: develop - SYNC_TARGET_BRANCH: develop - SYNC_BRANCH: sync-upstream-develop - -jobs: - sync-upstream: - runs-on: ubuntu-20.04 - - steps: - - name: Checkout repository - uses: actions/checkout@v2 - with: - ref: ${{ env.BASE_BRANCH }} - fetch-depth: 0 - - - name: Generate token - uses: tibdex/github-app-token@v1 - id: generate-token - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.APP_PRIVATE_KEY }} - - - name: Set git config for private repositories - run: | - git config --local --unset-all http.https://github.com/.extraheader || true - git config --global url.https://x-access-token:${{ steps.generate-token.outputs.token }}@github.com.insteadOf 'https://github.com' - - - name: Fetch upstream - run: | - git remote add upstream "${{ env.UPSTREAM_REPO }}" - git fetch -pPtf --all - - # To keep the base branch in "create-pull-request", checkout with "BASE_BRANCH" and reset to "SYNC_TARGET_BRANCH" - - name: Reset to sync target branch - run: | - git reset --hard upstream/${{ env.SYNC_TARGET_BRANCH }} - - - name: Create PR - id: create_pr - uses: peter-evans/create-pull-request@v3 - with: - token: ${{ steps.generate-token.outputs.token }} - commit-message: sync upstream develop - committer: GitHub - author: GitHub - signoff: false - base: ${{ env.BASE_BRANCH }} - branch: ${{ env.SYNC_BRANCH }} - delete-branch: true - title: sync upstream develop - body: | - sync upstream develop - labels: | - sync-upstream-develop - draft: false - - - name: Check outputs - run: | - echo "Pull Request Number - ${{ steps.create_pr.outputs.pull-request-number }}" - echo "Pull Request URL - ${{ steps.create_pr.outputs.pull-request-url }}" - - - name: Enable Auto-merge - if: steps.create_pr.outputs.pull-request-operation == 'created' - uses: peter-evans/enable-pull-request-automerge@v1 - with: - token: ${{ steps.generate-token.outputs.token }} - pull-request-number: ${{ steps.create_pr.outputs.pull-request-number }} - merge-method: merge diff --git a/.github/workflows/sync-upstream.yml b/.github/workflows/sync-upstream.yml index 934cb0bb9f..09d7f0629f 100644 --- a/.github/workflows/sync-upstream.yml +++ b/.github/workflows/sync-upstream.yml @@ -1,77 +1,28 @@ -name: sync upstream +name: sync-upstream on: schedule: - - cron: "0 19 * * *" # run at 4 AM JST + - cron: 0 19 * * * # run at 4 AM JST workflow_dispatch: -env: - UPSTREAM_REPO: https://github.com/tier4/autoware_launcher.git - BASE_BRANCH: main - SYNC_TARGET_BRANCH: main - SYNC_BRANCH: sync-upstream - jobs: sync-upstream: - runs-on: ubuntu-20.04 - + runs-on: ubuntu-latest steps: - - name: Checkout repository - uses: actions/checkout@v2 - with: - ref: ${{ env.BASE_BRANCH }} - fetch-depth: 0 - - name: Generate token - uses: tibdex/github-app-token@v1 id: generate-token + uses: tibdex/github-app-token@v1 with: app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.APP_PRIVATE_KEY }} - - - name: Set git config for private repositories - run: | - git config --local --unset-all http.https://github.com/.extraheader || true - git config --global url.https://x-access-token:${{ steps.generate-token.outputs.token }}@github.com.insteadOf 'https://github.com' - - - name: Fetch upstream - run: | - git remote add upstream "${{ env.UPSTREAM_REPO }}" - git fetch -pPtf --all - - # To keep the base branch in "create-pull-request", checkout with "BASE_BRANCH" and reset to "SYNC_TARGET_BRANCH" - - name: Reset to sync target branch - run: | - git reset --hard upstream/${{ env.SYNC_TARGET_BRANCH }} - - - name: Create PR - id: create_pr - uses: peter-evans/create-pull-request@v3 - with: - token: ${{ steps.generate-token.outputs.token }} - commit-message: sync upstream - committer: GitHub - author: GitHub - signoff: false - base: ${{ env.BASE_BRANCH }} - branch: ${{ env.SYNC_BRANCH }} - delete-branch: true - title: sync upstream - body: | - sync upstream - labels: | - sync-upstream - draft: false - - - name: Check outputs - run: | - echo "Pull Request Number - ${{ steps.create_pr.outputs.pull-request-number }}" - echo "Pull Request URL - ${{ steps.create_pr.outputs.pull-request-url }}" + private_key: ${{ secrets.PRIVATE_KEY }} - - name: Enable Auto-merge - if: steps.create_pr.outputs.pull-request-operation == 'created' - uses: peter-evans/enable-pull-request-automerge@v1 + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@tier4/proposal with: token: ${{ steps.generate-token.outputs.token }} - pull-request-number: ${{ steps.create_pr.outputs.pull-request-number }} - merge-method: merge + base-branch: tier4/universe + sync-pr-branch: sync-upstream + sync-target-repository: https://github.com/tier4/autoware_launch.git + sync-target-branch: tier4/universe + pr-title: "chore: sync upstream" + auto-merge-method: merge diff --git a/.github/workflows/update-pre-commit.yml b/.github/workflows/update-pre-commit.yml deleted file mode 100644 index d4a2f277d6..0000000000 --- a/.github/workflows/update-pre-commit.yml +++ /dev/null @@ -1,42 +0,0 @@ -name: Update pre-commit - -on: - schedule: - - cron: "0 19 * * 0" # run at 4 AM JST on Sundays - workflow_dispatch: - -jobs: - update-pre-commit: - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v2 - - - name: Generate token - uses: tibdex/github-app-token@v1 - id: generate-token - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.APP_PRIVATE_KEY }} - - - name: Setup Python - uses: actions/setup-python@v2 - with: - python-version: 3.8 - - - name: Install pre-commit - run: pip install pre-commit - - - name: Run pre-commit autoupdate - run: pre-commit autoupdate - - - name: Create Pull Request - uses: peter-evans/create-pull-request@v3 - with: - token: ${{ steps.generate-token.outputs.token }} - base: main - branch: update/pre-commit-autoupdate - title: Auto-update pre-commit hooks - commit-message: Auto-update pre-commit hooks - body: | - Update versions of tools in pre-commit configs to latest version - labels: dependencies diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 59d935c126..f5683bb90f 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -1,23 +1,8 @@ -# To install: -# -# pip install pre-commit -# -# To use: -# -# pre-commit run -a -# -# Or: -# -# pre-commit install # (runs every time you commit in git) -# -# To update this file: -# -# pre-commit autoupdate -# -# See https://github.com/pre-commit/pre-commit +ci: + autofix_commit_msg: "ci(pre-commit): autofix" + autoupdate_commit_msg: "ci(pre-commit): autoupdate" repos: - # Standard hooks - repo: https://github.com/pre-commit/pre-commit-hooks rev: v4.0.1 hooks: @@ -33,37 +18,48 @@ repos: args: [--markdown-linebreak-ext=md] - repo: https://github.com/igorshubovych/markdownlint-cli - rev: v0.29.0 + rev: v0.30.0 hooks: - id: markdownlint - args: ["-c", ".markdownlint.yaml", "--fix"] + args: [-c, .markdownlint.yaml, --fix] - repo: https://github.com/pre-commit/mirrors-prettier - rev: v2.4.1 + rev: v2.5.0 hooks: - id: prettier + - repo: https://github.com/adrienverge/yamllint + rev: v1.26.3 + hooks: + - id: yamllint + - repo: https://github.com/tier4/pre-commit-hooks-ros rev: v0.4.0 hooks: - id: prettier-package-xml - id: sort-package-xml - - repo: https://github.com/gruntwork-io/pre-commit - rev: v0.1.17 + - repo: https://github.com/shellcheck-py/shellcheck-py + rev: v0.8.0.1 hooks: - id: shellcheck + - repo: https://github.com/scop/pre-commit-shfmt + rev: v3.4.1-1 + hooks: + - id: shfmt + args: [-w, -s, -i=4] + - repo: https://github.com/pycqa/isort - rev: 5.9.3 + rev: 5.10.1 hooks: - id: isort - repo: https://github.com/psf/black - rev: 21.9b0 + rev: 21.11b1 hooks: - id: black - args: ["--line-length=100"] + args: [--line-length=100] - repo: https://github.com/PyCQA/flake8 rev: 4.0.1 @@ -71,14 +67,26 @@ repos: - id: flake8 additional_dependencies: [ - "flake8-blind-except", - "flake8-builtins", - "flake8-class-newline", - "flake8-comprehensions", - "flake8-deprecated", - "flake8-docstrings", - "flake8-import-order", - "flake8-quotes", + flake8-blind-except, + flake8-builtins, + flake8-class-newline, + flake8-comprehensions, + flake8-deprecated, + flake8-docstrings, + flake8-import-order, + flake8-quotes, ] -exclude: ".svg" + - repo: https://github.com/pre-commit/mirrors-clang-format + rev: v12.0.1 + hooks: + - id: clang-format + + - repo: https://github.com/cpplint/cpplint + rev: 1.5.5 + hooks: + - id: cpplint + args: [--quiet] + exclude: .cu + +exclude: .svg diff --git a/perception_launch/config/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml b/perception_launch/config/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml index 955a9e197e..781ccb806b 100644 --- a/perception_launch/config/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml +++ b/perception_launch/config/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml @@ -5,7 +5,7 @@ pcl_grid_map_extraction: x: 0.0 y: 0.0 z: 0.0 - rotation: #intrinsic rotation X-Y-Z (r-p-y)sequence + rotation: # intrinsic rotation X-Y-Z (r-p-y)sequence r: 0.0 p: 0.0 y: 0.0 From 19f2e448746f7fabefd918064fded7e5672224c0 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 1 Feb 2022 20:47:12 +0900 Subject: [PATCH 361/851] chore: minor update CI settings (#179) Signed-off-by: Kenji Miyake --- .github/get_modified_package.sh | 76 --------------------------------- .github/sync-files.yaml | 2 +- 2 files changed, 1 insertion(+), 77 deletions(-) delete mode 100755 .github/get_modified_package.sh diff --git a/.github/get_modified_package.sh b/.github/get_modified_package.sh deleted file mode 100755 index 7f9cd4b2f1..0000000000 --- a/.github/get_modified_package.sh +++ /dev/null @@ -1,76 +0,0 @@ -#!/bin/bash -# Search for packages that have been modified from the main branch. -# Usage: get_modified_package.sh - -set -e - -SCRIPT_DIR=$(readlink -f "$(dirname "$0")") -ROOT_DIR=$(readlink -f "$SCRIPT_DIR"/../) - -# Parse arguments -args=() -while [ "${1:-}" != "" ]; do - case "$1" in - *) - args+=("$1") - ;; - esac - shift -done - -base_branch="${args[0]}" - -# Check args -if [ "$base_branch" = "" ]; then - echo -e "\e[31mPlease input a valid base_branch as the 1st argument.\e[m" - exit 1 -fi - -function find_package_dir() { - [ "$1" == "" ] && return 1 - - target_dir=$(dirname "$1") - while true; do - parent_dir=$(dirname "$target_dir") - - # Exit if no parent found - if [ "$parent_dir" = "$target_dir" ]; then - return 0 - fi - - # Output package name if package.xml found - if [ -f "$target_dir/package.xml" ]; then - if [ ! -f "$target_dir/COLCON_IGNORE" ]; then - echo "$target_dir" - return 0 - fi - fi - - # Move to parent dir - target_dir=$parent_dir - done - - return 1 -} - -# Find modified files from base branch -modified_files=$(git diff --name-only "$base_branch"...HEAD) - -# Find modified packages -modified_package_dirs=() -for modified_file in $modified_files; do - modified_package_dir=$(find_package_dir "$ROOT_DIR/$modified_file") - - if [ "$modified_package_dir" != "" ]; then - modified_package_dirs+=("$modified_package_dir") - fi -done - -# Get package names from paths -if [ "${#modified_package_dirs[@]}" != "0" ]; then - modified_packages=$(colcon list --names-only --paths "${modified_package_dirs[@]}") -fi - -# Output -# shellcheck disable=SC2086 -echo ::set-output name=package_list::$modified_packages diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 7a2da49689..3f7279a744 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -1,6 +1,7 @@ - repository: autowarefoundation/autoware files: - source: .github/dependabot.yaml + - source: .github/workflows/automatic-rebase.yaml - source: .github/workflows/pre-commit-optional.yaml - source: .github/workflows/semantic-pull-request.yaml - source: .github/workflows/spell-check.yaml @@ -16,7 +17,6 @@ - repository: autowarefoundation/autoware_common files: - - source: .github/workflows/automatic-rebase.yaml - source: .github/workflows/build-and-test.yaml - source: .github/workflows/build-and-test-pr.yaml - source: .github/workflows/pre-commit.yaml From 3be690c1ae3c58c2c21b76e05534e1b5cdcf5bf6 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 1 Feb 2022 13:22:28 +0000 Subject: [PATCH 362/851] [pre-commit.ci] pre-commit autoupdate (#178) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit updates: - [github.com/pre-commit/pre-commit-hooks: v4.0.1 → v4.1.0](https://github.com/pre-commit/pre-commit-hooks/compare/v4.0.1...v4.1.0) - [github.com/igorshubovych/markdownlint-cli: v0.29.0 → v0.30.0](https://github.com/igorshubovych/markdownlint-cli/compare/v0.29.0...v0.30.0) - [github.com/pre-commit/mirrors-prettier: v2.4.1 → v2.5.1](https://github.com/pre-commit/mirrors-prettier/compare/v2.4.1...v2.5.1) - [github.com/pycqa/isort: 5.9.3 → 5.10.1](https://github.com/pycqa/isort/compare/5.9.3...5.10.1) - [github.com/psf/black: 21.9b0 → 22.1.0](https://github.com/psf/black/compare/21.9b0...22.1.0) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .github/workflows/{sync-upstream.yml => sync-upstream.yaml} | 0 .pre-commit-config.yaml | 6 +++--- 2 files changed, 3 insertions(+), 3 deletions(-) rename .github/workflows/{sync-upstream.yml => sync-upstream.yaml} (100%) diff --git a/.github/workflows/sync-upstream.yml b/.github/workflows/sync-upstream.yaml similarity index 100% rename from .github/workflows/sync-upstream.yml rename to .github/workflows/sync-upstream.yaml diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index f5683bb90f..0f5ae2f622 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -4,7 +4,7 @@ ci: repos: - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.0.1 + rev: v4.1.0 hooks: - id: check-json - id: check-merge-conflict @@ -24,7 +24,7 @@ repos: args: [-c, .markdownlint.yaml, --fix] - repo: https://github.com/pre-commit/mirrors-prettier - rev: v2.5.0 + rev: v2.5.1 hooks: - id: prettier @@ -56,7 +56,7 @@ repos: - id: isort - repo: https://github.com/psf/black - rev: 21.11b1 + rev: 22.1.0 hooks: - id: black args: [--line-length=100] From 181c2c911c3de46928e9dfacd628afe21a286c72 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Thu, 3 Feb 2022 08:55:33 +0900 Subject: [PATCH 363/851] chore: fix CI settings (#182) Signed-off-by: Kenji Miyake --- .github/sync-files.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 3f7279a744..dd26b448aa 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -10,7 +10,7 @@ - source: .markdownlint.yaml - source: .pre-commit-config-optional.yaml - source: .prettierignore - - source: .prettierrc + - source: .prettierrc.yaml - source: .yamllint.yaml - source: CPPLINT.cfg - source: setup.cfg From 42fca870919c036697d5e7400146823939fbca05 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-bot[bot]" <98652886+tier4-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 3 Feb 2022 10:31:43 +0900 Subject: [PATCH 364/851] chore: sync files (#180) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-pr.yaml | 17 +++++++++++++++++ .github/workflows/build-and-test.yaml | 17 +++++++++++++++++ .yamllint.yaml | 3 +++ 3 files changed, 37 insertions(+) diff --git a/.github/workflows/build-and-test-pr.yaml b/.github/workflows/build-and-test-pr.yaml index c9f5ed6ac7..c610b7dbd7 100644 --- a/.github/workflows/build-and-test-pr.yaml +++ b/.github/workflows/build-and-test-pr.yaml @@ -36,6 +36,23 @@ jobs: target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} build-depends-repos: build_depends.repos + - name: Check the existence of coverage files + id: check-file-existence + uses: autowarefoundation/autoware-github-actions/check-file-existence@tier4/proposal + with: + files: | + lcov/total_coverage.info + coveragepy/.coverage + condition: or + + - name: Upload coverage to CodeCov + if: ${{ steps.check-file-existence.outputs.exists == 'true' }} + uses: codecov/codecov-action@v2 + with: + files: lcov/total_coverage.info,coveragepy/.coverage + fail_ci_if_error: true + verbose: true + clang-tidy: runs-on: ubuntu-latest container: ros:galactic diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index a51dc52a57..cf7b809264 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -35,3 +35,20 @@ jobs: rosdistro: galactic target-packages: ${{ steps.get-self-packages.outputs.self-packages }} build-depends-repos: build_depends.repos + + - name: Check the existence of coverage files + id: check-file-existence + uses: autowarefoundation/autoware-github-actions/check-file-existence@tier4/proposal + with: + files: | + lcov/total_coverage.info + coveragepy/.coverage + condition: or + + - name: Upload coverage to CodeCov + if: ${{ steps.check-file-existence.outputs.exists == 'true' }} + uses: codecov/codecov-action@v2 + with: + files: lcov/total_coverage.info,coveragepy/.coverage + fail_ci_if_error: true + verbose: true diff --git a/.yamllint.yaml b/.yamllint.yaml index 1d4ee33eca..6228c70f02 100644 --- a/.yamllint.yaml +++ b/.yamllint.yaml @@ -5,6 +5,9 @@ ignore: | *.param.yaml rules: + braces: + level: error + max-spaces-inside: 1 # To format with Prettier comments: level: error min-spaces-from-content: 1 # To be compatible with C++ and Python From 2a7102be3e802f3cc1788bd9852d38f832c26dff Mon Sep 17 00:00:00 2001 From: "tier4-autoware-bot[bot]" <98652886+tier4-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 4 Feb 2022 10:21:50 +0900 Subject: [PATCH 365/851] chore: sync files (#184) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .prettierrc.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.prettierrc.yaml b/.prettierrc.yaml index ef9b1b85a7..48b0552e3f 100644 --- a/.prettierrc.yaml +++ b/.prettierrc.yaml @@ -1,2 +1,2 @@ -printWidth: 120 +printWidth: 100 tabWidth: 2 From 6be345d5f27bcbbf8c8971a749a3a6b4a9bc420f Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Fri, 4 Feb 2022 16:21:42 +0900 Subject: [PATCH 366/851] feat: add paricle param (#181) Signed-off-by: YamatoAndo --- localization_launch/config/ndt_scan_matcher.param.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/localization_launch/config/ndt_scan_matcher.param.yaml b/localization_launch/config/ndt_scan_matcher.param.yaml index d04b872f14..ae5a39dd99 100644 --- a/localization_launch/config/ndt_scan_matcher.param.yaml +++ b/localization_launch/config/ndt_scan_matcher.param.yaml @@ -26,6 +26,9 @@ # Threshold for deciding whether to trust the estimation result converged_param_transform_probability: 3.0 + # The number of particles to estimate initial pose + initial_estimate_particles_num: 100 + # neighborhood search method in OMP # 0=KDTREE, 1=DIRECT26, 2=DIRECT7, 3=DIRECT1 omp_neighborhood_search_method: 0 From 183a303535e0679152aaad7d843778e92cf96add Mon Sep 17 00:00:00 2001 From: "tier4-autoware-bot[bot]" <98652886+tier4-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 4 Feb 2022 18:23:21 +0900 Subject: [PATCH 367/851] chore: sync files (#185) * chore: sync files Signed-off-by: GitHub * Update sync-files.yaml Co-authored-by: kenji-miyake Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .github/sync-files.yaml | 1 - .github/workflows/automatic-rebase.yaml | 29 ------------------------- 2 files changed, 30 deletions(-) delete mode 100644 .github/workflows/automatic-rebase.yaml diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index dd26b448aa..8b8832ef90 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -1,7 +1,6 @@ - repository: autowarefoundation/autoware files: - source: .github/dependabot.yaml - - source: .github/workflows/automatic-rebase.yaml - source: .github/workflows/pre-commit-optional.yaml - source: .github/workflows/semantic-pull-request.yaml - source: .github/workflows/spell-check.yaml diff --git a/.github/workflows/automatic-rebase.yaml b/.github/workflows/automatic-rebase.yaml deleted file mode 100644 index 8f6dc2b300..0000000000 --- a/.github/workflows/automatic-rebase.yaml +++ /dev/null @@ -1,29 +0,0 @@ -name: automatic-rebase - -on: - issue_comment: - types: - - created - -jobs: - automatic-rebase: - if: ${{ github.event.issue.pull_request != '' && contains(github.event.comment.body, '/rebase') }} - runs-on: ubuntu-latest - steps: - - name: Generate token - id: generate-token - uses: tibdex/github-app-token@v1 - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.PRIVATE_KEY }} - - - name: Check out repository - uses: actions/checkout@v2 - with: - token: ${{ steps.generate-token.outputs.token }} - fetch-depth: 0 - - - name: Automatic rebase - uses: cirrus-actions/rebase@1.5 - env: - GITHUB_TOKEN: ${{ steps.generate-token.outputs.token }} From bc591f3b7f43d9cc23398f4e57fe82dd9beb687d Mon Sep 17 00:00:00 2001 From: "tier4-autoware-bot[bot]" <98652886+tier4-autoware-bot[bot]@users.noreply.github.com> Date: Sat, 5 Feb 2022 21:46:26 +0900 Subject: [PATCH 368/851] chore: sync files (#186) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-pr.yaml | 2 +- .github/workflows/build-and-test.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-and-test-pr.yaml b/.github/workflows/build-and-test-pr.yaml index c610b7dbd7..de3fc25e6f 100644 --- a/.github/workflows/build-and-test-pr.yaml +++ b/.github/workflows/build-and-test-pr.yaml @@ -6,7 +6,7 @@ on: jobs: build-and-test: runs-on: ubuntu-latest - container: ros:galactic + container: ghcr.io/autowarefoundation/autoware-universe:latest steps: - name: Cancel previous runs uses: styfle/cancel-workflow-action@0.9.1 diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index cf7b809264..5331dd336e 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -12,7 +12,7 @@ on: jobs: build-and-test: runs-on: ubuntu-latest - container: ros:galactic + container: ghcr.io/autowarefoundation/autoware-universe:latest steps: - name: Check out repository uses: actions/checkout@v2 From 1e73d9f8548da2322e1d7b1130cc2dc32969c2a8 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Sun, 6 Feb 2022 01:38:48 +0900 Subject: [PATCH 369/851] chore: sync system config (#187) Signed-off-by: wep21 --- .github/sync-files.yaml | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 8b8832ef90..96a8c99bc5 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -19,3 +19,14 @@ - source: .github/workflows/build-and-test.yaml - source: .github/workflows/build-and-test-pr.yaml - source: .github/workflows/pre-commit.yaml + +- repository: autowarefoundation/autoware.universe + files: + - source: system/ad_service_state_monitor/config/ad_service_state_monitor.param.yaml + dest: system_launch/config/ad_service_state_monitor.param.yaml + - source: system/ad_service_state_monitor/config/ad_service_state_monitor.planning_simulation.param.yaml + dest: system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml + - source: system/system_error_monitor/config/system_error_monitor.param.yaml + dest: system_launch/config/system_error_monitor.param.yaml + - source: system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml + dest: system_launch/config/system_error_monitor.planning_simulation.param.yaml From cda271dbf8cc7aec147c44c6efbf23c02200e0e0 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-bot[bot]" <98652886+tier4-autoware-bot[bot]@users.noreply.github.com> Date: Sun, 6 Feb 2022 01:45:03 +0900 Subject: [PATCH 370/851] chore: sync files (#189) Signed-off-by: GitHub Co-authored-by: wep21 --- .../ad_service_state_monitor.param.yaml | 155 ++++++++++++++++++ ...ate_monitor.planning_simulation.param.yaml | 134 +++++++++++++++ .../config/system_error_monitor.param.yaml | 50 ++++++ ...ror_monitor.planning_simulation.param.yaml | 50 ++++++ 4 files changed, 389 insertions(+) create mode 100644 system_launch/config/ad_service_state_monitor.param.yaml create mode 100644 system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml create mode 100644 system_launch/config/system_error_monitor.param.yaml create mode 100644 system_launch/config/system_error_monitor.planning_simulation.param.yaml diff --git a/system_launch/config/ad_service_state_monitor.param.yaml b/system_launch/config/ad_service_state_monitor.param.yaml new file mode 100644 index 0000000000..03610e09f1 --- /dev/null +++ b/system_launch/config/ad_service_state_monitor.param.yaml @@ -0,0 +1,155 @@ +# Autoware State Monitor Parameters +/**: + ros__parameters: + # modules_names: string array + module_names: [ + "map", + "sensing", + "perception", + "localization", + "planning", + "control", + "vehicle", + "system" + ] + + # Topic Config + ## names: string array + ## configs: top level + ### names used to declare parameter group + #### module: string + #### timeout[s]: double (0: none) + #### warn_rate[hz]: double (0: none) + topic_configs: + names: [ + "/map/vector_map", + "/map/pointcloud_map", + "/perception/obstacle_segmentation/pointcloud", + "/initialpose3d", + "/localization/pose_twist_fusion_filter/pose", + "/perception/object_recognition/objects", + "/planning/mission_planning/route", + "/planning/scenario_planning/trajectory", + "/control/trajectory_follower/control_cmd", + "/control/command/control_cmd", + "/vehicle/status/velocity_status", + "/vehicle/status/steering_status", + "/system/emergency/control_cmd" + ] + + configs: + /map/vector_map: + module: "map" + timeout: 0.0 + warn_rate: 0.0 + type: "autoware_auto_mapping_msgs/msg/HADMapBin" + transient_local: True + + /map/pointcloud_map: + module: "map" + timeout: 0.0 + warn_rate: 0.0 + type: "sensor_msgs/msg/PointCloud2" + transient_local: True + + /perception/obstacle_segmentation/pointcloud: + module: "sensing" + timeout: 1.0 + warn_rate: 5.0 + type: "sensor_msgs/msg/PointCloud2" + best_effort: True + + /initialpose3d: + module: "localization" + timeout: 0.0 + warn_rate: 0.0 + type: "geometry_msgs/msg/PoseWithCovarianceStamped" + + /localization/pose_twist_fusion_filter/pose: + module: "localization" + timeout: 1.0 + warn_rate: 5.0 + type: "geometry_msgs/msg/PoseStamped" + + # Can be both with feature array or without + # In prediction.launch.xml this is set to without + /perception/object_recognition/objects: + module: "perception" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_perception_msgs/msg/PredictedObjects" + # This topic could have two different types depending on the launch flags used. + # The implementation of subscriptions in ROS2 does not allow for multiple types + # to be defined for a topic. By default this is set to not use have features. + # type: ["tier4_perception_msgs/msg/DynamicObjectArray", "tier4_perception_msgs/msg/DynamicObjectWithFeatureArray"] + + /planning/mission_planning/route: + module: "planning" + timeout: 0.0 + warn_rate: 0.0 + type: "autoware_auto_planning_msgs/msg/HADMapRoute" + transient_local: True + + /planning/scenario_planning/trajectory: + module: "planning" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_planning_msgs/msg/Trajectory" + + /control/trajectory_follower/control_cmd: + module: "control" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_control_msgs/msg/AckermannControlCommand" + + /control/command/control_cmd: + module: "control" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_control_msgs/msg/AckermannControlCommand" + + /vehicle/status/velocity_status: + module: "vehicle" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_vehicle_msgs/msg/VelocityReport" + + /vehicle/status/steering_status: + module: "vehicle" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_vehicle_msgs/msg/SteeringReport" + + /system/emergency/control_cmd: + module: "system" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_control_msgs/msg/AckermannControlCommand" + + # Param Config + ## names: string array + ## configs: top level + ### names used to declare parameter group + #### module: string + # param_configs: + # names: ["/vehicle_info"] + # configs: + # /vehicle_info: + # module: "vehicle" + + # TF Config + ## names: string array + ## configs: top level + ### names used to declare parameter group + #### module: string + #### from: string + #### to: string + #### timeout[s]: double (0: none) + tf_configs: + names: ["map_to_base_link"] + configs: + map_to_base_link: + module: "localization" + from: "map" + to: "base_link" + timeout: 1.0 diff --git a/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml b/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml new file mode 100644 index 0000000000..41928923a0 --- /dev/null +++ b/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml @@ -0,0 +1,134 @@ +# Autoware State Monitor: Planning Simulator Parameters +/**: + ros__parameters: + # modules_names: string array + module_names: [ + "map", + "sensing", + "perception", + "localization", + "planning", + "control", + "vehicle", + "system" + ] + +# Topic Config + ## names: string array + ## configs: top level + ### names used to declare parameter group + #### module: string + #### timeout[s]: double (0: none) + #### warn_rate[hz]: double (0: none) + topic_configs: + names: [ + "/map/vector_map", + "/map/pointcloud_map", + "/perception/object_recognition/objects", + "/initialpose2d", + "/planning/mission_planning/route", + "/planning/scenario_planning/trajectory", + "/control/trajectory_follower/control_cmd", + "/control/command/control_cmd", + "/vehicle/status/velocity_status", + "/vehicle/status/steering_status", + "/system/emergency/control_cmd" + ] + + configs: + /map/vector_map: + module: "map" + timeout: 0.0 + warn_rate: 0.0 + type: "autoware_auto_mapping_msgs/msg/HADMapBin" + transient_local: True + + /map/pointcloud_map: + module: "map" + timeout: 0.0 + warn_rate: 0.0 + type: "sensor_msgs/msg/PointCloud2" + transient_local: True + + /perception/object_recognition/objects: + module: "perception" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_perception_msgs/msg/PredictedObjects" + + /initialpose2d: + module: "localization" + timeout: 0.0 + warn_rate: 0.0 + type: "geometry_msgs/msg/PoseWithCovarianceStamped" + + /planning/mission_planning/route: + module: "planning" + timeout: 0.0 + warn_rate: 0.0 + type: "autoware_auto_planning_msgs/msg/HADMapRoute" + transient_local: True + + /planning/scenario_planning/trajectory: + module: "planning" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_planning_msgs/msg/Trajectory" + + /control/trajectory_follower/control_cmd: + module: "control" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_control_msgs/msg/AckermannControlCommand" + + /control/command/control_cmd: + module: "control" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_control_msgs/msg/AckermannControlCommand" + + /vehicle/status/velocity_status: + module: "vehicle" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_vehicle_msgs/msg/VelocityReport" + + /vehicle/status/steering_status: + module: "vehicle" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_vehicle_msgs/msg/SteeringReport" + + /system/emergency/control_cmd: + module: "system" + timeout: 1.0 + warn_rate: 5.0 + type: "autoware_auto_control_msgs/msg/AckermannControlCommand" + + # Param Config + ## names: string array + ## configs: top level + ### names used to declare parameter group + #### module: string + # param_configs: + # names: ["/vehicle_info"] + # configs: + # /vehicle_info: + # module: "vehicle" + + # TF Config + ## names: string array + ## configs: top level + ### names used to declare parameter group + #### module: string + #### from: string + #### to: string + #### timeout[s]: double (0: none) + tf_configs: + names: ["map_to_base_link"] + configs: + map_to_base_link: + module: "localization" + from: "map" + to: "base_link" + timeout: 1.0 diff --git a/system_launch/config/system_error_monitor.param.yaml b/system_launch/config/system_error_monitor.param.yaml new file mode 100644 index 0000000000..b9a5a4fa79 --- /dev/null +++ b/system_launch/config/system_error_monitor.param.yaml @@ -0,0 +1,50 @@ +# Description: +# name: diag name +# sf_at: diag level where it becomes Safe Fault +# lf_at: diag level where it becomes Latent Fault +# spf_at: diag level where it becomes Single Point Fault +# auto_recovery: Determines whether the system will automatically recover when it recovers from an error. +# +# Note: +# empty-value for sf_at, lf_at and spf_at is "none" +# default values are: +# sf_at: "none" +# lf_at: "warn" +# spf_at: "error" +# auto_recovery: "true" +--- +/**: + ros__parameters: + required_modules: + autonomous_driving: + /autoware/control/autonomous_driving/node_alive_monitoring: default + /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default + /autoware/control/control_command_gate/node_alive_monitoring: default + + /autoware/localization/node_alive_monitoring: default + /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } + /autoware/localization/performance_monitoring/localization_accuracy: default + + /autoware/map/node_alive_monitoring: default + + /autoware/perception/node_alive_monitoring: default + + /autoware/planning/node_alive_monitoring: default + /autoware/planning/performance_monitoring/trajectory_validation: default + + /autoware/sensing/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "none", spf_at: "none" } + + /autoware/vehicle/node_alive_monitoring: default + + external_control: + /autoware/control/control_command_gate/node_alive_monitoring: default + /autoware/control/external_control/external_command_selector/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + + /autoware/vehicle/node_alive_monitoring: default diff --git a/system_launch/config/system_error_monitor.planning_simulation.param.yaml b/system_launch/config/system_error_monitor.planning_simulation.param.yaml new file mode 100644 index 0000000000..ce081b75b2 --- /dev/null +++ b/system_launch/config/system_error_monitor.planning_simulation.param.yaml @@ -0,0 +1,50 @@ +# Description: +# name: diag name +# sf_at: diag level where it becomes Safe Fault +# lf_at: diag level where it becomes Latent Fault +# spf_at: diag level where it becomes Single Point Fault +# auto_recovery: Determines whether the system will automatically recover when it recovers from an error. +# +# Note: +# empty-value for sf_at, lf_at and spf_at is "none" +# default values are: +# sf_at: "none" +# lf_at: "warn" +# spf_at: "error" +# auto_recovery: "true" +--- +/**: + ros__parameters: + required_modules: + autonomous_driving: + /autoware/control/autonomous_driving/node_alive_monitoring: default + /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default + /autoware/control/control_command_gate/node_alive_monitoring: default + + /autoware/localization/node_alive_monitoring: default + # /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } + # /autoware/localization/performance_monitoring/localization_accuracy: default + + /autoware/map/node_alive_monitoring: default + + /autoware/perception/node_alive_monitoring: default + + /autoware/planning/node_alive_monitoring: default + /autoware/planning/performance_monitoring/trajectory_validation: default + + /autoware/sensing/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + # /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "error", spf_at: "none" } + + /autoware/vehicle/node_alive_monitoring: default + + external_control: + /autoware/control/control_command_gate/node_alive_monitoring: default + /autoware/control/external_control/external_command_selector/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + + /autoware/vehicle/node_alive_monitoring: default From 1898e69f4b8eaf401a4c20f18f8f648b036df1e8 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Sun, 6 Feb 2022 01:52:24 +0900 Subject: [PATCH 371/851] chore: replace system config in system launch (#188) Signed-off-by: wep21 --- 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 1eb54a4a5c..1292853c7e 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -23,15 +23,15 @@ - - + + - - + + From 34090d22cbe5e83f5270dffe6ce3214d1a046a9a Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 7 Feb 2022 11:55:56 +0900 Subject: [PATCH 372/851] feat: adds additional configuration flags for behavior_path_planner (#171) * feat: adds additional configuration flags for behavior_path_planner The additional configuration is used to allows avoidance over lane with same and different direction, as well as allows safety margin between linestring and ego. This is a `.iv` launcher https://github.com/tier4/autoware_launcher/pull/496 port. Related PR: https://github.com/autowarefoundation/autoware.universe/pull/285 https://github.com/autowarefoundation/autoware.universe/pull/287 Signed-off-by: Muhammad Zulfaqar Azmi * Change lateral_collision_margion to 1.0 to reflect changes. The decision to change the parameter value to 1.0 is made after performing drivable area experiment at Odaiba areas on 2nd of February 2022 and meeting between planning control team on 3rd of February 2022. Signed-off-by: Muhammad Zulfaqar Azmi * fix: slightly increase the safety buffer. This increases the shift length to 1.7 + 0.5 * vehicle width. The decision to increase is based on the discussion between planning team and also the advice from the FI team. Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_planner/avoidance/avoidance.param.yaml | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index bfe310b737..4ddd16a8f7 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -7,11 +7,15 @@ detection_area_right_expand_dist: 0.0 detection_area_left_expand_dist: 1.0 + enable_avoidance_over_same_direction: true + enable_avoidance_over_opposite_direction: true + threshold_distance_object_is_on_center: 1.0 # [m] threshold_speed_object_is_stopped: 1.0 # [m/s] object_check_forward_distance: 150.0 # [m] object_check_backward_distance: 2.0 # [m] - lateral_collision_margin: 2.0 # [m] + lateral_collision_margin: 1.0 # [m] + lateral_collision_safety_buffer: 0.7 # [m] prepare_time: 2.0 # [s] min_prepare_distance: 1.0 # [m] @@ -20,6 +24,8 @@ min_nominal_avoidance_speed: 7.0 # [m/s] min_sharp_avoidance_speed: 1.0 # [m/s] + road_shoulder_safety_margin: 0.5 # [m] + max_right_shift_length: 5.0 max_left_shift_length: 5.0 From 8f85f10bbf5bb7287614d9f9ccb1cddb7e6cb220 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Mon, 7 Feb 2022 18:31:38 +0900 Subject: [PATCH 373/851] feat(behavior_velocity): add path marker visualization (#190) Signed-off-by: tanaka3 --- autoware_launch/rviz/autoware.rviz | 2 ++ 1 file changed, 2 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index d899c433b8..424c1e577d 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1141,6 +1141,8 @@ Visualization Manager: obstacle: false sidewalk: false slow factor_text: true + path_raw: false + path_interp: false Topic: Depth: 5 Durability Policy: Volatile From d7823f5903667ba1a06c34e437dd5972e58f4cda Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 8 Feb 2022 09:47:17 +0900 Subject: [PATCH 374/851] chore: sync files (#193) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-pr.yaml | 2 +- .github/workflows/build-and-test.yaml | 6 ++---- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/.github/workflows/build-and-test-pr.yaml b/.github/workflows/build-and-test-pr.yaml index de3fc25e6f..98e91d8807 100644 --- a/.github/workflows/build-and-test-pr.yaml +++ b/.github/workflows/build-and-test-pr.yaml @@ -50,7 +50,7 @@ jobs: uses: codecov/codecov-action@v2 with: files: lcov/total_coverage.info,coveragepy/.coverage - fail_ci_if_error: true + fail_ci_if_error: false verbose: true clang-tidy: diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 5331dd336e..a9ee40cb8e 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -2,15 +2,13 @@ name: build-and-test on: push: - branches: - - main - - tier4/proposal schedule: - cron: 0 19 * * * # run at 4 AM JST workflow_dispatch: jobs: build-and-test: + if: ${{ github.event_name != 'push' || github.ref_name == github.event.repository.default_branch }} runs-on: ubuntu-latest container: ghcr.io/autowarefoundation/autoware-universe:latest steps: @@ -50,5 +48,5 @@ jobs: uses: codecov/codecov-action@v2 with: files: lcov/total_coverage.info,coveragepy/.coverage - fail_ci_if_error: true + fail_ci_if_error: false verbose: true From ab8b90c48a719cc1b390861a9bf4c0b672447f5e Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 8 Feb 2022 18:20:41 +0900 Subject: [PATCH 375/851] chore: sync files (#194) * chore: sync files Signed-off-by: GitHub * chore: update workflow files name Signed-off-by: h-ohta Co-authored-by: h-ohta Co-authored-by: h-ohta --- .github/sync-files.yaml | 4 +- .github/workflows/build-and-test-pr.yaml | 85 ------------------------ .github/workflows/spell-check.yaml | 16 ----- 3 files changed, 2 insertions(+), 103 deletions(-) delete mode 100644 .github/workflows/build-and-test-pr.yaml delete mode 100644 .github/workflows/spell-check.yaml diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 96a8c99bc5..c9c88fec58 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -3,7 +3,7 @@ - source: .github/dependabot.yaml - source: .github/workflows/pre-commit-optional.yaml - source: .github/workflows/semantic-pull-request.yaml - - source: .github/workflows/spell-check.yaml + - source: .github/workflows/spell-check-differential.yaml - source: .clang-format - source: .markdown-link-check.json - source: .markdownlint.yaml @@ -17,7 +17,7 @@ - repository: autowarefoundation/autoware_common files: - source: .github/workflows/build-and-test.yaml - - source: .github/workflows/build-and-test-pr.yaml + - source: .github/workflows/build-and-test-differential.yaml - source: .github/workflows/pre-commit.yaml - repository: autowarefoundation/autoware.universe diff --git a/.github/workflows/build-and-test-pr.yaml b/.github/workflows/build-and-test-pr.yaml deleted file mode 100644 index 98e91d8807..0000000000 --- a/.github/workflows/build-and-test-pr.yaml +++ /dev/null @@ -1,85 +0,0 @@ -name: build-and-test-pr - -on: - pull_request: - -jobs: - build-and-test: - runs-on: ubuntu-latest - container: ghcr.io/autowarefoundation/autoware-universe:latest - steps: - - name: Cancel previous runs - uses: styfle/cancel-workflow-action@0.9.1 - - - name: Check out repository - uses: actions/checkout@v2 - with: - fetch-depth: 0 - - - name: Remove exec_depend - uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal - - - name: Register AutonomouStuff repository - uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal - with: - rosdistro: galactic - - - name: Get modified packages - id: get-modified-packages - uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal - - - name: Build and test - if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} - uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal - with: - rosdistro: galactic - target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} - build-depends-repos: build_depends.repos - - - name: Check the existence of coverage files - id: check-file-existence - uses: autowarefoundation/autoware-github-actions/check-file-existence@tier4/proposal - with: - files: | - lcov/total_coverage.info - coveragepy/.coverage - condition: or - - - name: Upload coverage to CodeCov - if: ${{ steps.check-file-existence.outputs.exists == 'true' }} - uses: codecov/codecov-action@v2 - with: - files: lcov/total_coverage.info,coveragepy/.coverage - fail_ci_if_error: false - verbose: true - - clang-tidy: - runs-on: ubuntu-latest - container: ros:galactic - needs: build-and-test - steps: - - name: Check out repository - uses: actions/checkout@v2 - with: - fetch-depth: 0 - - - name: Remove exec_depend - uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal - - - name: Register AutonomouStuff repository - uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal - with: - rosdistro: galactic - - - name: Get modified packages - id: get-modified-packages - uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal - - - name: Run clang-tidy - if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} - uses: autowarefoundation/autoware-github-actions/clang-tidy@tier4/proposal - with: - rosdistro: galactic - target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} - clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/tier4/proposal/.clang-tidy - build-depends-repos: build_depends.repos diff --git a/.github/workflows/spell-check.yaml b/.github/workflows/spell-check.yaml deleted file mode 100644 index 43a75891a3..0000000000 --- a/.github/workflows/spell-check.yaml +++ /dev/null @@ -1,16 +0,0 @@ -name: spell-check - -on: - pull_request: - -jobs: - spell-check: - runs-on: ubuntu-latest - steps: - - name: Check out repository - uses: actions/checkout@v2 - - - name: Run spell-check - uses: autowarefoundation/autoware-github-actions/spell-check@tier4/proposal - with: - cspell-json-url: https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json From e5625b65c4f7d9e0f91adbf2b6004e25bd57183b Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 8 Feb 2022 18:25:37 +0900 Subject: [PATCH 376/851] chore: sync files (#195) Signed-off-by: GitHub Co-authored-by: h-ohta --- .../build-and-test-differential.yaml | 85 +++++++++++++++++++ .../workflows/spell-check-differential.yaml | 16 ++++ 2 files changed, 101 insertions(+) create mode 100644 .github/workflows/build-and-test-differential.yaml create mode 100644 .github/workflows/spell-check-differential.yaml diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml new file mode 100644 index 0000000000..1ba8540a18 --- /dev/null +++ b/.github/workflows/build-and-test-differential.yaml @@ -0,0 +1,85 @@ +name: build-and-test-differential + +on: + pull_request: + +jobs: + build-and-test-differential: + runs-on: ubuntu-latest + container: ghcr.io/autowarefoundation/autoware-universe:latest + steps: + - name: Cancel previous runs + uses: styfle/cancel-workflow-action@0.9.1 + + - name: Check out repository + uses: actions/checkout@v2 + with: + fetch-depth: 0 + + - name: Remove exec_depend + uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal + + - name: Register AutonomouStuff repository + uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal + with: + rosdistro: galactic + + - name: Get modified packages + id: get-modified-packages + uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal + + - name: Build and test + if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} + uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal + with: + rosdistro: galactic + target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + build-depends-repos: build_depends.repos + + - name: Check the existence of coverage files + id: check-file-existence + uses: autowarefoundation/autoware-github-actions/check-file-existence@tier4/proposal + with: + files: | + lcov/total_coverage.info + coveragepy/.coverage + condition: or + + - name: Upload coverage to CodeCov + if: ${{ steps.check-file-existence.outputs.exists == 'true' }} + uses: codecov/codecov-action@v2 + with: + files: lcov/total_coverage.info,coveragepy/.coverage + fail_ci_if_error: false + verbose: true + + clang-tidy-differential: + runs-on: ubuntu-latest + container: ros:galactic + needs: build-and-test-differential + steps: + - name: Check out repository + uses: actions/checkout@v2 + with: + fetch-depth: 0 + + - name: Remove exec_depend + uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal + + - name: Register AutonomouStuff repository + uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal + with: + rosdistro: galactic + + - name: Get modified packages + id: get-modified-packages + uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal + + - name: Run clang-tidy + if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} + uses: autowarefoundation/autoware-github-actions/clang-tidy@tier4/proposal + with: + rosdistro: galactic + target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/tier4/proposal/.clang-tidy + build-depends-repos: build_depends.repos diff --git a/.github/workflows/spell-check-differential.yaml b/.github/workflows/spell-check-differential.yaml new file mode 100644 index 0000000000..484c369024 --- /dev/null +++ b/.github/workflows/spell-check-differential.yaml @@ -0,0 +1,16 @@ +name: spell-check-differential + +on: + pull_request: + +jobs: + spell-check-differential: + runs-on: ubuntu-latest + steps: + - name: Check out repository + uses: actions/checkout@v2 + + - name: Run spell-check + uses: autowarefoundation/autoware-github-actions/spell-check@tier4/proposal + with: + cspell-json-url: https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json From 3114c8ad17725b0af361c5492cbe7d3875be5f4b Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Tue, 8 Feb 2022 19:42:23 +0900 Subject: [PATCH 377/851] feat: lateral controller param (#191) * feat: define lat_controller_param_path * feat: change for trajectory_follower params * add args for lat_controller_param_path --- autoware_launch/launch/autoware.launch.xml | 1 + .../launch/logging_simulator.launch.xml | 1 + .../launch/planning_simulator.launch.xml | 1 + .../mpc_follower/mpc_follower.param.yaml | 57 ------------------- ...ler.param.yaml => mpc_follower.param.yaml} | 0 .../pure_pursuit.param.yaml | 0 control_launch/launch/control.launch.py | 26 ++++----- 7 files changed, 14 insertions(+), 72 deletions(-) delete mode 100644 control_launch/config/mpc_follower/mpc_follower.param.yaml rename control_launch/config/trajectory_follower/{lateral_controller.param.yaml => mpc_follower.param.yaml} (100%) rename control_launch/config/{pure_pursuit => trajectory_follower}/pure_pursuit.param.yaml (100%) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 71a7c54eb4..c375241125 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -71,6 +71,7 @@ + > diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 90c2813f98..b94aa67dee 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -103,6 +103,7 @@ + > diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 94fff17ea4..22c38e2e8c 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -50,6 +50,7 @@ + > 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 e11651495e..0000000000 --- a/control_launch/config/mpc_follower/mpc_follower.param.yaml +++ /dev/null @@ -1,57 +0,0 @@ -/**: - ros__parameters: - # -- system -- - ctrl_period: 0.03 # control period [s] - traj_resample_dist: 0.1 # path resampling interval [m] - use_steer_prediction: false # flag for using steer prediction (do not use steer measurement) - admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value - admissible_yaw_error_rad: 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_ref_steer: 15 # point-to-point index distance used in curvature calculation (for steer command reference): curvature is calculated from three points p(i-num), p(i), p(i+num) - curvature_smoothing_num_traj: 15 # point-to-point index distance used in curvature calculation (for trajectory): 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_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 curvature" 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 - - # -- 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 approximation) [s] - steer_lim_deg: 40.0 # steering angle limit [deg] - 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/trajectory_follower/lateral_controller.param.yaml b/control_launch/config/trajectory_follower/mpc_follower.param.yaml similarity index 100% rename from control_launch/config/trajectory_follower/lateral_controller.param.yaml rename to control_launch/config/trajectory_follower/mpc_follower.param.yaml diff --git a/control_launch/config/pure_pursuit/pure_pursuit.param.yaml b/control_launch/config/trajectory_follower/pure_pursuit.param.yaml similarity index 100% rename from control_launch/config/pure_pursuit/pure_pursuit.param.yaml rename to control_launch/config/trajectory_follower/pure_pursuit.param.yaml diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 5b3a4fdd9b..fef26da44a 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -32,21 +32,9 @@ def launch_setup(context, *args, **kwargs): - lateral_controller_mode = LaunchConfiguration("lateral_controller_mode").perform(context) - if lateral_controller_mode == "mpc_follower": - lat_controller_param_path = ( - FindPackageShare("control_launch").perform(context) - + "/config/trajectory_follower/lateral_controller.param.yaml" - ) - with open(lat_controller_param_path, "r") as f: - lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] - elif lateral_controller_mode == "pure_pursuit": - lat_controller_param_path = ( - FindPackageShare("control_launch").perform(context) - + "/config/pure_pursuit/pure_pursuit.param.yaml" - ) - with open(lat_controller_param_path, "r") as f: - lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] + lat_controller_param_path = LaunchConfiguration("lat_controller_param_path").perform(context) + with open(lat_controller_param_path, "r") as f: + lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] lon_controller_param_path = LaunchConfiguration("lon_controller_param_path").perform(context) with open(lon_controller_param_path, "r") as f: lon_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] @@ -316,6 +304,14 @@ def add_launch_arg(name: str, default_value=None, description=None): ) # parameter file path + add_launch_arg( + "lat_controller_param_path", + [ + FindPackageShare("control_launch"), + "/config/trajectory_follower/mpc_follower.param.yaml", + ], + "path to the parameter file of lateral controller. default is `mpc_follower`", + ) add_launch_arg( "lon_controller_param_path", [ From 7ff7530d343bf8c98befdcdc72ef8523fe398651 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Wed, 9 Feb 2022 01:19:32 +0900 Subject: [PATCH 378/851] chore: fix wrong essential param to optional (#197) * fix wrong param line * move pointcloud_container_name param to optional --- autoware_launch/launch/autoware.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index c375241125..3312290ed0 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -4,10 +4,10 @@ - - + + From 3261e8968133d5284f0f13f96fc362ee9a46bac1 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Wed, 9 Feb 2022 13:20:34 +0900 Subject: [PATCH 379/851] fix: typo extra `>` (#199) --- autoware_launch/launch/autoware.launch.xml | 2 +- autoware_launch/launch/logging_simulator.launch.xml | 2 +- autoware_launch/launch/planning_simulator.launch.xml | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 3312290ed0..4a3793464e 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -71,7 +71,7 @@ - > + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index b94aa67dee..fa108fae75 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -103,7 +103,7 @@ - > + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 22c38e2e8c..4f325124d9 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -50,7 +50,7 @@ - > + From bb6f0a5ad72afdcb7c5054f0155e3287c29c2b9b Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Wed, 9 Feb 2022 15:50:49 +0900 Subject: [PATCH 380/851] Chore arrange perception rviz topics (#196) * feat(autoware_launch): add occupancy grid vizualization Signed-off-by: tanaka3 * feat(autoware_launch): add object recognition namespace to rviz Signed-off-by: tanaka3 --- autoware_launch/rviz/autoware.rviz | 307 ++++++++++++++++------------- 1 file changed, 168 insertions(+), 139 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 424c1e577d..9c2e3bc8a1 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -722,178 +722,207 @@ Visualization Manager: Name: Segmentation - Class: rviz_common/Group Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/DetectedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: DetectedObjects + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/object_recognition/detection/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 + Value: true + Enabled: false + Name: Detection + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/TrackedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: TrackedObjects + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/object_recognition/tracking/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 + Value: true + Enabled: false + Name: Tracking + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/PredictedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: PredictedObjects + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/object_recognition/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 + Value: true Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: DetectedObjects - Namespaces: - {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/detection/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 - Value: true - Enabled: false - Name: Detection + Name: Prediction + Enabled: true + Name: ObjectRecognition - Class: rviz_common/Group Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/TrackedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true + - Class: rviz_default_plugins/Image Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: TrackedObjects - Namespaces: - {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: RecognitionResultOnImage + Normalize Range: true Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/object_recognition/tracking/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 + Value: /perception/traffic_light_recognition/debug/rois Value: true - Enabled: false - Name: Tracking - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/PredictedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true + - Class: rviz_default_plugins/MarkerArray Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: PredictedObjects + Name: MapBasedDetectionResult Namespaces: {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/object_recognition/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 + Value: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers Value: true Enabled: true - Name: Prediction + Name: TrafficLight - Class: rviz_common/Group Displays: - - Class: rviz_default_plugins/Image + - Alpha: 0.5 + Class: rviz_default_plugins/Map + Color Scheme: map + Draw Behind: false Enabled: true - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: RecognitionResultOnImage - Normalize Range: true + Name: Map Topic: Depth: 5 Durability Policy: Volatile + Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/traffic_light_recognition/debug/rois - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: MapBasedDetectionResult - Namespaces: - {} - Topic: + Value: /perception/occupancy_grid_map/map + Update 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: /perception/occupancy_grid_map/map_updates + Use Timestamp: false Value: true - Enabled: true - Name: TrafficLight + Enabled: false + Name: OccupancyGrid Enabled: true Name: Perception - Class: rviz_common/Group From e0eba25b4f2d950164338de51c221503fbca037d Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 10 Feb 2022 12:05:04 +0900 Subject: [PATCH 381/851] fix: delete unused in control_launch (#200) * fix: delete unused in control.launch.py * fix: delete velocity_controller.param.yaml --- .../velocity_controller.param.yaml | 68 ------------------- control_launch/launch/control.launch.py | 14 ---- 2 files changed, 82 deletions(-) delete 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 deleted file mode 100644 index f9a2f02b58..0000000000 --- a/control_launch/config/velocity_controller/velocity_controller.param.yaml +++ /dev/null @@ -1,68 +0,0 @@ -/**: - ros__parameters: - # delay compensation - delay_compensation_time: 0.17 - - # slope compensation - enable_slope_compensation: true - - # state transition - drive_state_stop_dist: 0.5 - stopping_state_stop_dist: 0.5 - stopped_state_entry_vel: 0.01 - stopped_state_entry_acc: 0.1 - emergency_state_overshoot_stop_dist: 1.5 - emergency_state_traj_trans_dev: 3.0 - emergency_state_traj_rot_dev: 0.7854 - - # drive state - kp: 1.0 - ki: 0.1 - 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.0 - min_d_effort: 0.0 - lpf_vel_error_gain: 0.9 - current_velocity_threshold_pid_integration: 0.5 - - # smooth stop state - smooth_stop_max_strong_acc: -0.5 - smooth_stop_min_strong_acc: -0.8 - smooth_stop_weak_acc: -0.3 - smooth_stop_weak_stop_acc: -0.8 - smooth_stop_strong_stop_acc: -3.4 - smooth_stop_min_fast_vel: 0.5 - smooth_stop_min_running_vel: 0.01 - smooth_stop_min_running_acc: 0.01 - smooth_stop_weak_stop_time: 0.8 - smooth_stop_weak_stop_dist: -0.3 - smooth_stop_strong_stop_dist: -0.5 - - # stopped state - stopped_vel: 0.0 - stopped_acc: -3.4 - stopped_jerk: -5.0 - - # emergency state - emergency_vel: 0.0 - emergency_acc: -5.0 - emergency_jerk: -3.0 - - # acceleration limit - max_acc: 3.0 - min_acc: -5.0 - - # jerk limit - max_jerk: 2.0 - min_jerk: -5.0 - - # pitch - use_trajectory_for_pitch_calculation: false - lpf_pitch_gain: 0.95 - max_pitch_rad: 0.1 - min_pitch_rad: -0.1 diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index fef26da44a..1d5cf26548 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -103,12 +103,6 @@ def launch_setup(context, *args, **kwargs): ], parameters=[ lon_controller_param, - { - "control_rate": LaunchConfiguration("control_rate"), - "show_debug_info": LaunchConfiguration("show_debug_info"), - "enable_smooth_stop": LaunchConfiguration("enable_smooth_stop"), - "enable_pub_debug": LaunchConfiguration("enable_pub_debug"), - }, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) @@ -341,14 +335,6 @@ def add_launch_arg(name: str, default_value=None, description=None): [FindPackageShare("lane_departure_checker"), "/config/lane_departure_checker.param.yaml"], ) - # velocity controller - add_launch_arg("control_rate", "30.0", "control rate") - add_launch_arg("show_debug_info", "false", "show debug information") - add_launch_arg( - "enable_smooth_stop", "true", "enable smooth stop (in velocity controller state)" - ) - add_launch_arg("enable_pub_debug", "true", "enable to publish debug information") - # vehicle cmd gate add_launch_arg("use_emergency_handling", "false", "use emergency handling") add_launch_arg("use_external_emergency_stop", "true", "use external emergency stop") From 1a6058eb6d0c01a773128c926f06f12c0d85dd0f Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 10 Feb 2022 16:36:02 +0900 Subject: [PATCH 382/851] feat: add system_monitor parameters in sync-files (#201) --- .github/sync-files.yaml | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index c9c88fec58..9d07f31f3c 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -30,3 +30,17 @@ dest: system_launch/config/system_error_monitor.param.yaml - source: system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml dest: system_launch/config/system_error_monitor.planning_simulation.param.yaml + - source: system/system_monitor/config/cpu_monitor.param.yaml + dest: system_launch/config/system_monitor/cpu_monitor.param.yaml + - source: system/system_monitor/config/gpu_monitor.param.yaml + dest: system_launch/config/system_monitor/gpu_monitor.param.yaml + - source: system/system_monitor/config/hdd_monitor.param.yaml + dest: system_launch/config/system_monitor/hdd_monitor.param.yaml + - source: system/system_monitor/config/mem_monitor.param.yaml + dest: system_launch/config/system_monitor/mem_monitor.param.yaml + - source: system/system_monitor/config/net_monitor.param.yaml + dest: system_launch/config/system_monitor/net_monitor.param.yaml + - source: system/system_monitor/config/ntp_monitor.param.yaml + dest: system_launch/config/system_monitor/ntp_monitor.param.yaml + - source: system/system_monitor/config/process_monitor.param.yaml + dest: system_launch/config/system_monitor/process_monitor.param.yaml From 948a74edce6b74623155358e164b453612733dc8 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Thu, 10 Feb 2022 16:36:20 +0900 Subject: [PATCH 383/851] chore: sync files (#202) Signed-off-by: GitHub Co-authored-by: h-ohta --- system_launch/config/system_monitor/cpu_monitor.param.yaml | 5 ++--- system_launch/config/system_monitor/hdd_monitor.param.yaml | 2 +- system_launch/config/system_monitor/mem_monitor.param.yaml | 3 +-- system_launch/config/system_monitor/net_monitor.param.yaml | 3 ++- 4 files changed, 6 insertions(+), 7 deletions(-) diff --git a/system_launch/config/system_monitor/cpu_monitor.param.yaml b/system_launch/config/system_monitor/cpu_monitor.param.yaml index e9f91cb170..2f049519aa 100644 --- a/system_launch/config/system_monitor/cpu_monitor.param.yaml +++ b/system_launch/config/system_monitor/cpu_monitor.param.yaml @@ -1,8 +1,7 @@ /**: ros__parameters: - temp_warn: 90.0 - temp_error: 95.0 - usage_warn: 0.90 + usage_warn: 0.96 usage_error: 1.00 + usage_count: 2 usage_avg: true msr_reader_port: 7634 diff --git a/system_launch/config/system_monitor/hdd_monitor.param.yaml b/system_launch/config/system_monitor/hdd_monitor.param.yaml index 2b9bde71ea..817ff68814 100644 --- a/system_launch/config/system_monitor/hdd_monitor.param.yaml +++ b/system_launch/config/system_monitor/hdd_monitor.param.yaml @@ -4,7 +4,7 @@ num_disks: 1 disks: # Until multi type lists are allowed, name N the disks as disk0...disk{N-1} disk0: - name: /dev/sda + name: / temp_warn: 55.0 temp_error: 70.0 free_warn: 5120 # MB(8hour) diff --git a/system_launch/config/system_monitor/mem_monitor.param.yaml b/system_launch/config/system_monitor/mem_monitor.param.yaml index 93688d608a..f2da3972be 100644 --- a/system_launch/config/system_monitor/mem_monitor.param.yaml +++ b/system_launch/config/system_monitor/mem_monitor.param.yaml @@ -1,4 +1,3 @@ /**: ros__parameters: - usage_warn: 0.95 - usage_error: 0.99 + available_size: 1024 # MB diff --git a/system_launch/config/system_monitor/net_monitor.param.yaml b/system_launch/config/system_monitor/net_monitor.param.yaml index d0707ddba3..953d32d788 100644 --- a/system_launch/config/system_monitor/net_monitor.param.yaml +++ b/system_launch/config/system_monitor/net_monitor.param.yaml @@ -1,4 +1,5 @@ /**: ros__parameters: devices: ["*"] - usage_warn: 0.95 + traffic_reader_port: 7636 + monitor_program: "greengrass" From 3c83103e45fbc2f5dd752413550e185454322e61 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sat, 12 Feb 2022 04:11:53 +0900 Subject: [PATCH 384/851] chore: sync files (#203) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test.yaml | 1 + .github/workflows/spell-check-differential.yaml | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index a9ee40cb8e..338ead5c47 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -28,6 +28,7 @@ jobs: uses: autowarefoundation/autoware-github-actions/get-self-packages@tier4/proposal - name: Build and test + if: ${{ steps.get-self-packages.outputs.self-packages != '' }} uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal with: rosdistro: galactic diff --git a/.github/workflows/spell-check-differential.yaml b/.github/workflows/spell-check-differential.yaml index 484c369024..1b5c52cb40 100644 --- a/.github/workflows/spell-check-differential.yaml +++ b/.github/workflows/spell-check-differential.yaml @@ -13,4 +13,4 @@ jobs: - name: Run spell-check uses: autowarefoundation/autoware-github-actions/spell-check@tier4/proposal with: - cspell-json-url: https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json + cspell-json-url: https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/.cspell.json From 13bfd8b125f409600715f766f8bb90479ab72a9c Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 14 Feb 2022 15:44:19 +0900 Subject: [PATCH 385/851] chore: update settings of sync-files (#204) Signed-off-by: Kenji Miyake --- .github/sync-files.yaml | 27 +--------------------- .github/sync-param-files.yaml | 30 +++++++++++++++++++++++++ .github/workflows/sync-param-files.yaml | 23 +++++++++++++++++++ 3 files changed, 54 insertions(+), 26 deletions(-) create mode 100644 .github/sync-param-files.yaml create mode 100644 .github/workflows/sync-param-files.yaml diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 9d07f31f3c..30122a85ac 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -1,6 +1,7 @@ - repository: autowarefoundation/autoware files: - source: .github/dependabot.yaml + - source: .github/workflows/pre-commit.yaml - source: .github/workflows/pre-commit-optional.yaml - source: .github/workflows/semantic-pull-request.yaml - source: .github/workflows/spell-check-differential.yaml @@ -18,29 +19,3 @@ files: - source: .github/workflows/build-and-test.yaml - source: .github/workflows/build-and-test-differential.yaml - - source: .github/workflows/pre-commit.yaml - -- repository: autowarefoundation/autoware.universe - files: - - source: system/ad_service_state_monitor/config/ad_service_state_monitor.param.yaml - dest: system_launch/config/ad_service_state_monitor.param.yaml - - source: system/ad_service_state_monitor/config/ad_service_state_monitor.planning_simulation.param.yaml - dest: system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml - - source: system/system_error_monitor/config/system_error_monitor.param.yaml - dest: system_launch/config/system_error_monitor.param.yaml - - source: system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml - dest: system_launch/config/system_error_monitor.planning_simulation.param.yaml - - source: system/system_monitor/config/cpu_monitor.param.yaml - dest: system_launch/config/system_monitor/cpu_monitor.param.yaml - - source: system/system_monitor/config/gpu_monitor.param.yaml - dest: system_launch/config/system_monitor/gpu_monitor.param.yaml - - source: system/system_monitor/config/hdd_monitor.param.yaml - dest: system_launch/config/system_monitor/hdd_monitor.param.yaml - - source: system/system_monitor/config/mem_monitor.param.yaml - dest: system_launch/config/system_monitor/mem_monitor.param.yaml - - source: system/system_monitor/config/net_monitor.param.yaml - dest: system_launch/config/system_monitor/net_monitor.param.yaml - - source: system/system_monitor/config/ntp_monitor.param.yaml - dest: system_launch/config/system_monitor/ntp_monitor.param.yaml - - source: system/system_monitor/config/process_monitor.param.yaml - dest: system_launch/config/system_monitor/process_monitor.param.yaml diff --git a/.github/sync-param-files.yaml b/.github/sync-param-files.yaml new file mode 100644 index 0000000000..ffa78c1690 --- /dev/null +++ b/.github/sync-param-files.yaml @@ -0,0 +1,30 @@ +- repository: tier4/autoware.universe + files: + # system + ## ad_service_state_monitor + - source: system/ad_service_state_monitor/config/ad_service_state_monitor.param.yaml + dest: system_launch/config/ad_service_state_monitor.param.yaml + - source: system/ad_service_state_monitor/config/ad_service_state_monitor.planning_simulation.param.yaml + dest: system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml + + ## system_error_monitor + - source: system/system_error_monitor/config/system_error_monitor.param.yaml + dest: system_launch/config/system_error_monitor.param.yaml + - source: system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml + dest: system_launch/config/system_error_monitor.planning_simulation.param.yaml + + ## system_monitor + - source: system/system_monitor/config/cpu_monitor.param.yaml + dest: system_launch/config/system_monitor/cpu_monitor.param.yaml + - source: system/system_monitor/config/gpu_monitor.param.yaml + dest: system_launch/config/system_monitor/gpu_monitor.param.yaml + - source: system/system_monitor/config/hdd_monitor.param.yaml + dest: system_launch/config/system_monitor/hdd_monitor.param.yaml + - source: system/system_monitor/config/mem_monitor.param.yaml + dest: system_launch/config/system_monitor/mem_monitor.param.yaml + - source: system/system_monitor/config/net_monitor.param.yaml + dest: system_launch/config/system_monitor/net_monitor.param.yaml + - source: system/system_monitor/config/ntp_monitor.param.yaml + dest: system_launch/config/system_monitor/ntp_monitor.param.yaml + - source: system/system_monitor/config/process_monitor.param.yaml + dest: system_launch/config/system_monitor/process_monitor.param.yaml diff --git a/.github/workflows/sync-param-files.yaml b/.github/workflows/sync-param-files.yaml new file mode 100644 index 0000000000..763a8ee286 --- /dev/null +++ b/.github/workflows/sync-param-files.yaml @@ -0,0 +1,23 @@ +name: sync-param-files + +on: + schedule: + - cron: 0 19 * * * # run at 4 AM JST + workflow_dispatch: + +jobs: + sync-param-files: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-files + uses: autowarefoundation/autoware-github-actions/sync-files@tier4/proposal + with: + token: ${{ steps.generate-token.outputs.token }} + config: .github/sync-param-files.yaml From 701b58e5242b52cac8ca0362875922c3610fa45d Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 15 Feb 2022 11:42:36 +0900 Subject: [PATCH 386/851] feat(control_launch): remove unnecessary params (#206) Signed-off-by: Takayuki Murooka --- .../longitudinal_controller.param.yaml | 12 ------------ 1 file changed, 12 deletions(-) diff --git a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml index 38414ce96b..97fad61fac 100644 --- a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml +++ b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml @@ -70,15 +70,3 @@ lpf_pitch_gain: 0.95 max_pitch_rad: 0.1 min_pitch_rad: -0.1 - - # vehicle parameters - vehicle: - cg_to_front_m: 1.228 - cg_to_rear_m: 1.5618 - mass_kg: 2400.0 - mass_fl: 600.0 - mass_fr: 600.0 - mass_rl: 600.0 - mass_rr: 600.0 - cf: 155494.663 - cr: 155494.663 From 33a8edfc60244438917f485d0d9a542584455591 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Wed, 16 Feb 2022 11:38:29 +0900 Subject: [PATCH 387/851] chore: sync files (#208) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .../build-and-test-differential.yaml | 22 +++++++++---------- .github/workflows/build-and-test.yaml | 22 +++++++++---------- 2 files changed, 22 insertions(+), 22 deletions(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 1ba8540a18..1eddcc9b06 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -28,28 +28,28 @@ jobs: id: get-modified-packages uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal - - name: Build and test + - name: Build if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} - uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal + uses: autowarefoundation/autoware-github-actions/colcon-build@tier4/proposal with: rosdistro: galactic target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} build-depends-repos: build_depends.repos - - name: Check the existence of coverage files - id: check-file-existence - uses: autowarefoundation/autoware-github-actions/check-file-existence@tier4/proposal + - name: Test + id: test + if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} + uses: autowarefoundation/autoware-github-actions/colcon-test@tier4/proposal with: - files: | - lcov/total_coverage.info - coveragepy/.coverage - condition: or + rosdistro: galactic + target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + build-depends-repos: build_depends.repos - name: Upload coverage to CodeCov - if: ${{ steps.check-file-existence.outputs.exists == 'true' }} + if: ${{ steps.test.outputs.coverage-report-files != '' }} uses: codecov/codecov-action@v2 with: - files: lcov/total_coverage.info,coveragepy/.coverage + files: ${{ steps.test.outputs.coverage-report-files }} fail_ci_if_error: false verbose: true diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 338ead5c47..880f47192b 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -27,27 +27,27 @@ jobs: id: get-self-packages uses: autowarefoundation/autoware-github-actions/get-self-packages@tier4/proposal - - name: Build and test + - name: Build if: ${{ steps.get-self-packages.outputs.self-packages != '' }} - uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal + uses: autowarefoundation/autoware-github-actions/colcon-build@tier4/proposal with: rosdistro: galactic target-packages: ${{ steps.get-self-packages.outputs.self-packages }} build-depends-repos: build_depends.repos - - name: Check the existence of coverage files - id: check-file-existence - uses: autowarefoundation/autoware-github-actions/check-file-existence@tier4/proposal + - name: Test + if: ${{ steps.get-self-packages.outputs.self-packages != '' }} + id: test + uses: autowarefoundation/autoware-github-actions/colcon-test@tier4/proposal with: - files: | - lcov/total_coverage.info - coveragepy/.coverage - condition: or + rosdistro: galactic + target-packages: ${{ steps.get-self-packages.outputs.self-packages }} + build-depends-repos: build_depends.repos - name: Upload coverage to CodeCov - if: ${{ steps.check-file-existence.outputs.exists == 'true' }} + if: ${{ steps.test.outputs.coverage-report-files != '' }} uses: codecov/codecov-action@v2 with: - files: lcov/total_coverage.info,coveragepy/.coverage + files: ${{ steps.test.outputs.coverage-report-files }} fail_ci_if_error: false verbose: true From 00575bed99520d6add46faef0f3e5708a490f128 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Wed, 16 Feb 2022 16:36:23 +0900 Subject: [PATCH 388/851] feat(atutoware.rviz): disable selectable for pointcloud visualization (#207) Signed-off-by: YamatoAndo --- autoware_launch/rviz/autoware.rviz | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 9c2e3bc8a1..354513a70b 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -355,7 +355,7 @@ Visualization Manager: Min Intensity: 0 Name: PointCloudMap Position Transformer: XYZ - Selectable: true + Selectable: false Size (Pixels): 1 Size (m): 0.02 Style: Points @@ -424,7 +424,7 @@ Visualization Manager: Min Intensity: 0 Name: ConcatenatePointCloud Position Transformer: XYZ - Selectable: true + Selectable: false Size (Pixels): 1 Size (m): 0.02 Style: Points @@ -599,7 +599,7 @@ Visualization Manager: Min Intensity: 0 Name: Initial Position Transformer: XYZ - Selectable: true + Selectable: false Size (Pixels): 10 Size (m): 0.02 Style: Squares @@ -632,7 +632,7 @@ Visualization Manager: Min Intensity: 0 Name: Aligned Position Transformer: XYZ - Selectable: true + Selectable: false Size (Pixels): 10 Size (m): 0.02 Style: Squares @@ -705,7 +705,7 @@ Visualization Manager: Min Intensity: -5 Name: NoGroundPointCloud Position Transformer: XYZ - Selectable: true + Selectable: false Size (Pixels): 3 Size (m): 0.02 Style: Points From 176e9c937c80777d0d26e6f339bb9662530de068 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Fri, 18 Feb 2022 16:01:17 +0900 Subject: [PATCH 389/851] chore: sync files (#212) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 10 ---------- .github/workflows/build-and-test.yaml | 5 ----- 2 files changed, 15 deletions(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 1eddcc9b06..6e8ebef574 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -19,11 +19,6 @@ jobs: - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal - - name: Register AutonomouStuff repository - uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal - with: - rosdistro: galactic - - name: Get modified packages id: get-modified-packages uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal @@ -66,11 +61,6 @@ jobs: - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal - - name: Register AutonomouStuff repository - uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal - with: - rosdistro: galactic - - name: Get modified packages id: get-modified-packages uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 880f47192b..1e422cc380 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -18,11 +18,6 @@ jobs: - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal - - name: Register AutonomouStuff repository - uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal - with: - rosdistro: galactic - - name: Get self packages id: get-self-packages uses: autowarefoundation/autoware-github-actions/get-self-packages@tier4/proposal From 927534386a16a6a38679173cb7ccc884fe7c74cb Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 21 Feb 2022 11:53:27 +0900 Subject: [PATCH 390/851] feat(behavior path planner): update params of behavior path for dynamic drivable area (#209) --- .../behavior_path_planner.param.yaml | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index fcdcf5c78c..adce0a5088 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -7,8 +7,12 @@ backward_length_buffer_for_end_of_pull_out: 5.0 minimum_lane_change_length: 12.0 minimum_pull_over_length: 16.0 + drivable_area_resolution: 0.1 - drivable_area_width: 100.0 - drivable_area_height: 50.0 + drivable_lane_forward_length: 50.0 + drivable_lane_backward_length: 5.0 + drivable_lane_margin: 1.0 + drivable_area_margin: 6.0 + refine_goal_search_radius_range: 7.5 intersection_search_distance: 30.0 From 782e836bbefea3d5d87a787af12fd9df248f2d43 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 24 Feb 2022 17:06:58 +0900 Subject: [PATCH 391/851] feat: load global param (#216) * feat: load global param Signed-off-by: wep21 * chore: add comment about rosdistro migration Signed-off-by: wep21 --- autoware_launch/launch/autoware.launch.xml | 2 -- .../launch/logging_simulator.launch.xml | 2 -- .../ground_segmentation.launch.py | 21 +++++++++---------- .../launch/perception.launch.xml | 2 -- sensing_launch/README.md | 1 - sensing_launch/launch/sensing.launch.xml | 2 -- 6 files changed, 10 insertions(+), 20 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 4a3793464e..e8d661bfc6 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -44,7 +44,6 @@ - @@ -58,7 +57,6 @@ - diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index fa108fae75..9704254fb1 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -68,7 +68,6 @@ - @@ -86,7 +85,6 @@ - diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 0d790b8d16..d44af6fac0 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -48,17 +48,17 @@ def __init__(self, context): self.use_time_series_filter = self.ground_segmentation_param["use_time_series_filter"] def get_vehicle_info(self): - path = LaunchConfiguration("vehicle_param_file").perform(self.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"] + # TODO: need to rename key from "ros_params" to "global_params" after Humble + gp = self.context.launch_configurations.get("ros_params", {}) + p = {} + p["vehicle_length"] = gp["front_overhang"] + gp["wheel_base"] + gp["rear_overhang"] + p["vehicle_width"] = gp["wheel_tread"] + gp["left_overhang"] + gp["right_overhang"] + p["min_longitudinal_offset"] = -gp["rear_overhang"] + p["max_longitudinal_offset"] = gp["front_overhang"] + gp["wheel_base"] + p["min_lateral_offset"] = -(gp["wheel_tread"] / 2.0 + gp["right_overhang"]) + p["max_lateral_offset"] = gp["wheel_tread"] / 2.0 + gp["left_overhang"] p["min_height_offset"] = 0.0 - p["max_height_offset"] = p["vehicle_height"] + p["max_height_offset"] = gp["vehicle_height"] return p def get_vehicle_mirror_info(self): @@ -509,7 +509,6 @@ 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("use_multithread", "False") add_launch_arg("use_intra_process", "True") add_launch_arg("use_pointcloud_container", "False") diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 69d301df48..d3d179dd37 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -1,7 +1,6 @@ - @@ -35,7 +34,6 @@ - diff --git a/sensing_launch/README.md b/sensing_launch/README.md index 2a6b577a12..68d14582d0 100644 --- a/sensing_launch/README.md +++ b/sensing_launch/README.md @@ -16,7 +16,6 @@ You can include as follows in `*.launch.xml` to use `sensing.launch.xml`. - ``` diff --git a/sensing_launch/launch/sensing.launch.xml b/sensing_launch/launch/sensing.launch.xml index 715b8f9117..cc0393234b 100644 --- a/sensing_launch/launch/sensing.launch.xml +++ b/sensing_launch/launch/sensing.launch.xml @@ -2,7 +2,6 @@ - @@ -15,7 +14,6 @@ - From 347c1bfb2d9b00463a2fef47223628f211b812ce Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Fri, 25 Feb 2022 14:57:09 +0900 Subject: [PATCH 392/851] fix: add feature_remover after apollo segmentation (#217) Signed-off-by: tomoya.kimura --- ...ra_lidar_fusion_based_detection.launch.xml | 19 ++++++++++++++----- 1 file changed, 14 insertions(+), 5 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 dade43a98b..98bc1019d1 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 @@ -86,6 +86,7 @@ + @@ -93,13 +94,21 @@ + - - - - - + + + + + + + + + + + + From b46b9ee4445ca54123f6e79d436c27298a72fceb Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sun, 27 Feb 2022 19:17:46 +0000 Subject: [PATCH 393/851] chore: sync files (#222) * chore: sync files Signed-off-by: GitHub * Update sync-param-files.yaml Co-authored-by: kenji-miyake Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .github/workflows/sync-param-files.yaml | 3 +++ CPPLINT.cfg | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/.github/workflows/sync-param-files.yaml b/.github/workflows/sync-param-files.yaml index 763a8ee286..2fcf611f9d 100644 --- a/.github/workflows/sync-param-files.yaml +++ b/.github/workflows/sync-param-files.yaml @@ -21,3 +21,6 @@ jobs: with: token: ${{ steps.generate-token.outputs.token }} config: .github/sync-param-files.yaml + pr-branch: sync-param-files + pr-title: "chore: sync param files" + pr-commit-message: "chore: sync param files" diff --git a/CPPLINT.cfg b/CPPLINT.cfg index 4dbbe0596b..1e2521f0b6 100644 --- a/CPPLINT.cfg +++ b/CPPLINT.cfg @@ -9,5 +9,5 @@ filter=-whitespace/braces # we wrap open curly braces for namespaces, cl filter=-whitespace/indent # we don't indent keywords like public, protected and private with one space filter=-whitespace/parens # we allow closing parenthesis to be on the next line filter=-whitespace/semicolon # we allow the developer to decide about whitespace after a semicolon -filter=-build/header_guard # TODO(Kenji Miyake): Support ROS-style rule in cpplint or add auto-fix script in pre-commit +filter=-build/header_guard # we automatically fix the names of header guards using pre-commit filter=-build/include_order # we use the custom include order From 4851f81562a30223289a50c2391df422ecbb4241 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Tue, 1 Mar 2022 10:42:29 +0900 Subject: [PATCH 394/851] chore(perception_launch): update laserscan angle increment to pandar 64 level resolution (#220) Signed-off-by: taikitanaka --- .../launch/occupancy_grid_map/occupancy_grid_map.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py b/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py index 57e172ffda..ce2a53a7f4 100644 --- a/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py +++ b/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py @@ -59,7 +59,7 @@ def add_launch_arg(name: str, default_value=None): "max_height": 2.0, "angle_min": -3.141592, # -M_PI "angle_max": 3.141592, # M_PI - "angle_increment": 0.00436332222, # 0.25*M_PI/180.0 + "angle_increment": 0.0034906585, # 0.20*M_PI/180.0 "scan_time": 0.0, "range_min": 1.0, "range_max": 200.0, From 1b1213789820e7eca6e2250bb1fe9ff1eef5a326 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 2 Mar 2022 10:24:49 +0900 Subject: [PATCH 395/851] feat: add enable option for image decompressor (#224) * feat: add enable option for image decompressor Signed-off-by: wep21 * ci: fix flake8 Signed-off-by: wep21 --- .../traffic_light.launch.xml | 2 + .../traffic_light_node_container.launch.py | 48 +++++++++++-------- 2 files changed, 30 insertions(+), 20 deletions(-) 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 d86a8ccf19..99833e1fe1 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -1,6 +1,7 @@ + @@ -22,6 +23,7 @@ + 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 8993530343..3f16c9a043 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 @@ -15,7 +15,6 @@ import os from ament_index_python.packages import get_package_share_directory -import launch from launch import LaunchDescription from launch.actions import DeclareLaunchArgument from launch.actions import SetLaunchConfiguration @@ -38,6 +37,7 @@ def add_launch_arg(name: str, default_value=None, description=None): 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_image_decompressor", "True") add_launch_arg("enable_fine_detection", "True") add_launch_arg("input/image", "/sensing/camera/traffic_light/image_raw") @@ -82,22 +82,6 @@ def create_parameter_dict(*args): package="rclcpp_components", executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ - ComposableNode( - package="image_transport_decompressor", - plugin="image_preprocessor::ImageTransportDecompressor", - name="traffic_light_image_decompressor", - parameters=[{"encoding": "rgb8"}], - remappings=[ - ( - "~/input/compressed_image", - [LaunchConfiguration("input/image"), "/compressed"], - ), - ("~/output/raw_image", LaunchConfiguration("input/image")), - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ), ComposableNode( package="traffic_light_classifier", plugin="traffic_light::TrafficLightClassifierNodelet", @@ -146,6 +130,29 @@ def create_parameter_dict(*args): output="both", ) + decompressor_loader = LoadComposableNodes( + composable_node_descriptions=[ + ComposableNode( + package="image_transport_decompressor", + plugin="image_preprocessor::ImageTransportDecompressor", + name="traffic_light_image_decompressor", + parameters=[{"encoding": "rgb8"}], + remappings=[ + ( + "~/input/compressed_image", + [LaunchConfiguration("input/image"), "/compressed"], + ), + ("~/output/raw_image", LaunchConfiguration("input/image")), + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ), + ], + target_container=container, + condition=IfCondition(LaunchConfiguration("enable_image_decompressor")), + ) + ssd_fine_detector_param = create_parameter_dict( "onnx_file", "label_file", @@ -157,7 +164,7 @@ def create_parameter_dict(*args): ) ssd_fine_detector_param["mode"] = LaunchConfiguration("fine_detector_precision") - loader = LoadComposableNodes( + fine_detector_loader = LoadComposableNodes( composable_node_descriptions=[ ComposableNode( package="traffic_light_ssd_fine_detector", @@ -175,7 +182,7 @@ def create_parameter_dict(*args): ), ], target_container=container, - condition=launch.conditions.IfCondition(LaunchConfiguration("enable_fine_detection")), + condition=IfCondition(LaunchConfiguration("enable_fine_detection")), ) set_container_executable = SetLaunchConfiguration( @@ -196,6 +203,7 @@ def create_parameter_dict(*args): set_container_executable, set_container_mt_executable, container, - loader, + decompressor_loader, + fine_detector_loader, ] ) From c2fed614ad95a6d2eae47d3f7041db4bebeebe70 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Wed, 2 Mar 2022 11:08:37 +0900 Subject: [PATCH 396/851] feat(behavior_velocity): add merge from private marker (#223) * feat(behavior_velocity): add merge from private marker Signed-off-by: tanaka3 * feat(behavior_velocity): add factor text Signed-off-by: tanaka3 --- 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 354513a70b..c29581bd0d 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1075,6 +1075,20 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: MergeFromPrivate + Namespaces: + factor_text: true + stop_point_pose_line: false + stop_virtual_wall: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/merge_from_private + Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true Name: Blind Spot From d1edfd6e435936fbe6f74390e44a619709810c12 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 2 Mar 2022 11:26:50 +0900 Subject: [PATCH 397/851] chore: expose traffic light model path arg (#225) Signed-off-by: wep21 --- .../traffic_light.launch.xml | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) 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 99833e1fe1..462a895420 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -5,6 +5,18 @@ + + + + @@ -27,6 +39,10 @@ + + + + From 9cdc598b5729cf140e7f89b6e5f9eff6ca1982ce Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 2 Mar 2022 14:42:07 +0900 Subject: [PATCH 398/851] feat(autoware_launch, simulator_launch): move perception modules to simulator.launch.xml (#227) * feat(autoware_launch, simulator_launch): move perception modules to simulator.launch.xml Signed-off-by: Takayuki Murooka * remove unnecessary comment Signed-off-by: Takayuki Murooka --- .../launch/planning_simulator.launch.xml | 4 +- simulator_launch/launch/simulator.launch.xml | 43 ++++++++++++++++++- 2 files changed, 45 insertions(+), 2 deletions(-) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 4f325124d9..94664653c2 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -12,7 +12,8 @@ - + + @@ -70,6 +71,7 @@ + diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index 7fe691ff18..006f35985b 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -2,7 +2,8 @@ - + + @@ -24,6 +25,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 4da4b4dd54e8156c118c7bc8ad54a8be0d1e4b5c Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Thu, 3 Mar 2022 04:19:30 +0900 Subject: [PATCH 399/851] feat(ndt_scan_matcher): add the tolerance of initial pose (#211) * feat(ndt_scan_matcher): add the tolerance of initial pose Signed-off-by: YamatoAndo * change param name Signed-off-by: YamatoAndo * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization_launch/config/ndt_scan_matcher.param.yaml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/localization_launch/config/ndt_scan_matcher.param.yaml b/localization_launch/config/ndt_scan_matcher.param.yaml index ae5a39dd99..fd21436b39 100644 --- a/localization_launch/config/ndt_scan_matcher.param.yaml +++ b/localization_launch/config/ndt_scan_matcher.param.yaml @@ -29,6 +29,12 @@ # The number of particles to estimate initial pose initial_estimate_particles_num: 100 + # Tolerance of timestamp difference between initial_pose and sensor pointcloud. [sec] + initial_pose_timeout_sec: 1.0 + + # Tolerance of distance difference between two initial poses used for linear interpolation. [m] + initial_pose_distance_tolerance_m: 10.0 + # neighborhood search method in OMP # 0=KDTREE, 1=DIRECT26, 2=DIRECT7, 3=DIRECT1 omp_neighborhood_search_method: 0 From d0dfff50b3c5676ee63340bfb47a1d0f66b7f9db Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Thu, 3 Mar 2022 08:13:21 +0900 Subject: [PATCH 400/851] chore: sync files (#229) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 4 ++-- .github/workflows/build-and-test.yaml | 2 +- .github/workflows/pre-commit-optional.yaml | 2 +- .github/workflows/pre-commit.yaml | 2 +- .github/workflows/spell-check-differential.yaml | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 6e8ebef574..1ccc33765f 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -12,7 +12,7 @@ jobs: uses: styfle/cancel-workflow-action@0.9.1 - name: Check out repository - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: fetch-depth: 0 @@ -54,7 +54,7 @@ jobs: needs: build-and-test-differential steps: - name: Check out repository - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: fetch-depth: 0 diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 1e422cc380..975a8e9919 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -13,7 +13,7 @@ jobs: container: ghcr.io/autowarefoundation/autoware-universe:latest steps: - name: Check out repository - uses: actions/checkout@v2 + uses: actions/checkout@v3 - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal diff --git a/.github/workflows/pre-commit-optional.yaml b/.github/workflows/pre-commit-optional.yaml index 50b6778a25..0ccc7e59cb 100644 --- a/.github/workflows/pre-commit-optional.yaml +++ b/.github/workflows/pre-commit-optional.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v2 + uses: actions/checkout@v3 - name: Run pre-commit uses: autowarefoundation/autoware-github-actions/pre-commit@tier4/proposal diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml index 9eb501a19d..a1fc538110 100644 --- a/.github/workflows/pre-commit.yaml +++ b/.github/workflows/pre-commit.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v2 + uses: actions/checkout@v3 - name: Run pre-commit uses: autowarefoundation/autoware-github-actions/pre-commit@tier4/proposal diff --git a/.github/workflows/spell-check-differential.yaml b/.github/workflows/spell-check-differential.yaml index 1b5c52cb40..8a7b7da4f8 100644 --- a/.github/workflows/spell-check-differential.yaml +++ b/.github/workflows/spell-check-differential.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v2 + uses: actions/checkout@v3 - name: Run spell-check uses: autowarefoundation/autoware-github-actions/spell-check@tier4/proposal From 31fe5912a2d4eb5caadc6803df85ff14f78318ff Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Thu, 3 Mar 2022 04:42:56 +0000 Subject: [PATCH 401/851] chore: sync files (#230) * chore: sync files Signed-off-by: GitHub * remove tier4/proposal Signed-off-by: Kenji Miyake * change cron schedules Signed-off-by: Kenji Miyake * sync sync-files.yaml Signed-off-by: Kenji Miyake Co-authored-by: kenji-miyake Co-authored-by: Kenji Miyake --- .github/sync-files.yaml | 1 + .../workflows/build-and-test-differential.yaml | 16 ++++++++-------- .github/workflows/build-and-test.yaml | 10 +++++----- .github/workflows/pre-commit-optional.yaml | 2 +- .github/workflows/pre-commit.yaml | 2 +- .github/workflows/semantic-pull-request.yaml | 2 +- .github/workflows/spell-check-differential.yaml | 2 +- .github/workflows/sync-files.yaml | 4 ++-- .github/workflows/sync-param-files.yaml | 4 ++-- .github/workflows/sync-upstream.yaml | 4 ++-- 10 files changed, 24 insertions(+), 23 deletions(-) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 30122a85ac..34a7d476e1 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -19,3 +19,4 @@ files: - source: .github/workflows/build-and-test.yaml - source: .github/workflows/build-and-test-differential.yaml + - source: .github/workflows/sync-files.yaml diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 1ccc33765f..7e3d186886 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -17,15 +17,15 @@ jobs: fetch-depth: 0 - name: Remove exec_depend - uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal + uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 - name: Get modified packages id: get-modified-packages - uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal + uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1 - name: Build if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} - uses: autowarefoundation/autoware-github-actions/colcon-build@tier4/proposal + uses: autowarefoundation/autoware-github-actions/colcon-build@v1 with: rosdistro: galactic target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} @@ -34,7 +34,7 @@ jobs: - name: Test id: test if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} - uses: autowarefoundation/autoware-github-actions/colcon-test@tier4/proposal + uses: autowarefoundation/autoware-github-actions/colcon-test@v1 with: rosdistro: galactic target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} @@ -59,17 +59,17 @@ jobs: fetch-depth: 0 - name: Remove exec_depend - uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal + uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 - name: Get modified packages id: get-modified-packages - uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal + uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1 - name: Run clang-tidy if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} - uses: autowarefoundation/autoware-github-actions/clang-tidy@tier4/proposal + uses: autowarefoundation/autoware-github-actions/clang-tidy@v1 with: rosdistro: galactic target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} - clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/tier4/proposal/.clang-tidy + clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy build-depends-repos: build_depends.repos diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 975a8e9919..125d209ac1 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -3,7 +3,7 @@ name: build-and-test on: push: schedule: - - cron: 0 19 * * * # run at 4 AM JST + - cron: 0 0 * * * workflow_dispatch: jobs: @@ -16,15 +16,15 @@ jobs: uses: actions/checkout@v3 - name: Remove exec_depend - uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal + uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 - name: Get self packages id: get-self-packages - uses: autowarefoundation/autoware-github-actions/get-self-packages@tier4/proposal + uses: autowarefoundation/autoware-github-actions/get-self-packages@v1 - name: Build if: ${{ steps.get-self-packages.outputs.self-packages != '' }} - uses: autowarefoundation/autoware-github-actions/colcon-build@tier4/proposal + uses: autowarefoundation/autoware-github-actions/colcon-build@v1 with: rosdistro: galactic target-packages: ${{ steps.get-self-packages.outputs.self-packages }} @@ -33,7 +33,7 @@ jobs: - name: Test if: ${{ steps.get-self-packages.outputs.self-packages != '' }} id: test - uses: autowarefoundation/autoware-github-actions/colcon-test@tier4/proposal + uses: autowarefoundation/autoware-github-actions/colcon-test@v1 with: rosdistro: galactic target-packages: ${{ steps.get-self-packages.outputs.self-packages }} diff --git a/.github/workflows/pre-commit-optional.yaml b/.github/workflows/pre-commit-optional.yaml index 0ccc7e59cb..93e05dc2c7 100644 --- a/.github/workflows/pre-commit-optional.yaml +++ b/.github/workflows/pre-commit-optional.yaml @@ -11,6 +11,6 @@ jobs: uses: actions/checkout@v3 - name: Run pre-commit - uses: autowarefoundation/autoware-github-actions/pre-commit@tier4/proposal + uses: autowarefoundation/autoware-github-actions/pre-commit@v1 with: pre-commit-config: .pre-commit-config-optional.yaml diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml index a1fc538110..e1b72f7068 100644 --- a/.github/workflows/pre-commit.yaml +++ b/.github/workflows/pre-commit.yaml @@ -11,6 +11,6 @@ jobs: uses: actions/checkout@v3 - name: Run pre-commit - uses: autowarefoundation/autoware-github-actions/pre-commit@tier4/proposal + uses: autowarefoundation/autoware-github-actions/pre-commit@v1 with: pre-commit-config: .pre-commit-config.yaml diff --git a/.github/workflows/semantic-pull-request.yaml b/.github/workflows/semantic-pull-request.yaml index 0edf194633..71224c224e 100644 --- a/.github/workflows/semantic-pull-request.yaml +++ b/.github/workflows/semantic-pull-request.yaml @@ -9,4 +9,4 @@ on: jobs: semantic-pull-request: - uses: autowarefoundation/autoware-github-actions/.github/workflows/semantic-pull-request.yaml@tier4/proposal + uses: autowarefoundation/autoware-github-actions/.github/workflows/semantic-pull-request.yaml@v1 diff --git a/.github/workflows/spell-check-differential.yaml b/.github/workflows/spell-check-differential.yaml index 8a7b7da4f8..eb18ccdba3 100644 --- a/.github/workflows/spell-check-differential.yaml +++ b/.github/workflows/spell-check-differential.yaml @@ -11,6 +11,6 @@ jobs: uses: actions/checkout@v3 - name: Run spell-check - uses: autowarefoundation/autoware-github-actions/spell-check@tier4/proposal + uses: autowarefoundation/autoware-github-actions/spell-check@v1 with: cspell-json-url: https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/.cspell.json diff --git a/.github/workflows/sync-files.yaml b/.github/workflows/sync-files.yaml index 0c5b4b04fa..32f4613f6d 100644 --- a/.github/workflows/sync-files.yaml +++ b/.github/workflows/sync-files.yaml @@ -2,7 +2,7 @@ name: sync-files on: schedule: - - cron: 0 19 * * * # run at 4 AM JST + - cron: 0 0 * * * workflow_dispatch: jobs: @@ -17,6 +17,6 @@ jobs: private_key: ${{ secrets.PRIVATE_KEY }} - name: Run sync-files - uses: autowarefoundation/autoware-github-actions/sync-files@tier4/proposal + uses: autowarefoundation/autoware-github-actions/sync-files@v1 with: token: ${{ steps.generate-token.outputs.token }} diff --git a/.github/workflows/sync-param-files.yaml b/.github/workflows/sync-param-files.yaml index 2fcf611f9d..c119083f9d 100644 --- a/.github/workflows/sync-param-files.yaml +++ b/.github/workflows/sync-param-files.yaml @@ -2,7 +2,7 @@ name: sync-param-files on: schedule: - - cron: 0 19 * * * # run at 4 AM JST + - cron: 0 0 * * * workflow_dispatch: jobs: @@ -17,7 +17,7 @@ jobs: private_key: ${{ secrets.PRIVATE_KEY }} - name: Run sync-files - uses: autowarefoundation/autoware-github-actions/sync-files@tier4/proposal + uses: autowarefoundation/autoware-github-actions/sync-files@v1 with: token: ${{ steps.generate-token.outputs.token }} config: .github/sync-param-files.yaml diff --git a/.github/workflows/sync-upstream.yaml b/.github/workflows/sync-upstream.yaml index 09d7f0629f..68a0315fed 100644 --- a/.github/workflows/sync-upstream.yaml +++ b/.github/workflows/sync-upstream.yaml @@ -2,7 +2,7 @@ name: sync-upstream on: schedule: - - cron: 0 19 * * * # run at 4 AM JST + - cron: 0 0 * * * workflow_dispatch: jobs: @@ -17,7 +17,7 @@ jobs: private_key: ${{ secrets.PRIVATE_KEY }} - name: Run sync-branches - uses: autowarefoundation/autoware-github-actions/sync-branches@tier4/proposal + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 with: token: ${{ steps.generate-token.outputs.token }} base-branch: tier4/universe From 70102103ee3e083214160526f0855ecbbb245cc2 Mon Sep 17 00:00:00 2001 From: TakumiKozaka-T4 <70260442+TakumiKozaka-T4@users.noreply.github.com> Date: Thu, 3 Mar 2022 18:15:10 +0900 Subject: [PATCH 402/851] feat: add launch description for cpu usage adaptor (#210) Signed-off-by: TakumiKozaka-T4 --- .../launch/include/external_api_adaptor.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_api_launch/launch/include/external_api_adaptor.launch.py b/autoware_api_launch/launch/include/external_api_adaptor.launch.py index f81e88a77f..4f1295588a 100644 --- a/autoware_api_launch/launch/include/external_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/external_api_adaptor.launch.py @@ -29,6 +29,7 @@ def _create_api_node(node_name, class_name, **kwargs): def generate_launch_description(): components = [ + _create_api_node("cpu_usage", "CpuUsage"), _create_api_node("diagnostics", "Diagnostics"), _create_api_node("door", "Door"), _create_api_node("emergency", "Emergency"), From 5acb0a497be7c1e411211ca816e5522d44065c20 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Mon, 7 Mar 2022 13:44:43 +0900 Subject: [PATCH 403/851] fix: delete aip dependents (#235) * fix: delete aip dependents * Update package.xml Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- sensing_launch/package.xml | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/sensing_launch/package.xml b/sensing_launch/package.xml index 538895f408..b5012e35ed 100644 --- a/sensing_launch/package.xml +++ b/sensing_launch/package.xml @@ -9,10 +9,7 @@ Apache License 2.0 ament_cmake_auto - aip_x1_launch - aip_x2_launch - aip_xx1_launch - common_sensor_launch + ament_lint_auto autoware_lint_common From 3d81e9a8bf436e6f15fdf9aafcf9a0ffcc1be2f5 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 8 Mar 2022 15:44:38 +0900 Subject: [PATCH 404/851] chore: sync param files (#233) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- system_launch/config/ad_service_state_monitor.param.yaml | 2 +- .../ad_service_state_monitor.planning_simulation.param.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/system_launch/config/ad_service_state_monitor.param.yaml b/system_launch/config/ad_service_state_monitor.param.yaml index 03610e09f1..bfbb6beeaf 100644 --- a/system_launch/config/ad_service_state_monitor.param.yaml +++ b/system_launch/config/ad_service_state_monitor.param.yaml @@ -1,4 +1,4 @@ -# Autoware State Monitor Parameters +# AD Service State Monitor Parameters /**: ros__parameters: # modules_names: string array diff --git a/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml b/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml index 41928923a0..a3b20c4c94 100644 --- a/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml +++ b/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml @@ -1,4 +1,4 @@ -# Autoware State Monitor: Planning Simulator Parameters +# AD Service State Monitor: Planning Simulator Parameters /**: ros__parameters: # modules_names: string array From 6c1c98e0d8f95e524375f8d42ca49277a04aab36 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 8 Mar 2022 20:11:59 +0900 Subject: [PATCH 405/851] fix(trajectory_follower): change default param for curvature smoothing (#236) Signed-off-by: Takamasa Horibe --- .../config/trajectory_follower/mpc_follower.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/control_launch/config/trajectory_follower/mpc_follower.param.yaml b/control_launch/config/trajectory_follower/mpc_follower.param.yaml index 910aac218e..b3b9d60857 100644 --- a/control_launch/config/trajectory_follower/mpc_follower.param.yaml +++ b/control_launch/config/trajectory_follower/mpc_follower.param.yaml @@ -11,7 +11,7 @@ # -- 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_traj: 1 # point-to-point index distance used in curvature calculation (for trajectory): curvature is calculated from three points p(i-num), p(i), p(i+num) + curvature_smoothing_num_traj: 15 # point-to-point index distance used in curvature calculation (for trajectory): curvature is calculated from three points p(i-num), p(i), p(i+num) curvature_smoothing_num_ref_steer: 15 # point-to-point index distance used in curvature calculation (for steer command reference): curvature is calculated from three points p(i-num), p(i), p(i+num) # -- mpc optimization -- From 5fd4b9598ccbf408dc6cb6ceba5e986121d6903b Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Thu, 10 Mar 2022 11:30:50 +0900 Subject: [PATCH 406/851] fix(perception_launch): integration miss related to camera lidar fusion (#234) * fix(perception_launch): integration miss related to camera lidar fusion Signed-off-by: Yukihiro Saito * add detection by tracker Signed-off-by: Yukihiro Saito * Apply suggestions from code review Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --- ...ra_lidar_fusion_based_detection.launch.xml | 19 ++++++++++++++++--- .../lidar_based_detection.launch.xml | 2 +- 2 files changed, 17 insertions(+), 4 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 98bc1019d1..ba7933ce68 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 @@ -37,6 +37,7 @@ + @@ -68,10 +69,8 @@ - - @@ -101,7 +100,7 @@ - + @@ -111,9 +110,23 @@ + + + + + + + + + + + + + + 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 a836c4198f..692697d6d9 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 @@ -33,7 +33,7 @@ - + From e0d419848c0bf7029222867a4d2e374ed1f9c175 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Fri, 11 Mar 2022 00:22:35 +0900 Subject: [PATCH 407/851] feat: add iou gate (#237) Signed-off-by: Yukihiro Saito --- .../data_association_matrix.param.yaml | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml index 393bb949d0..385eb335c3 100644 --- a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml +++ b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml @@ -50,3 +50,13 @@ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #PEDESTRIAN 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #ANIMAL + min_iou_matrix: + #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL + [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN + 0.1, 0.3, 0.2, 0.2, 0.1, 0.1, 0.1, 0.1, #CAR + 0.1, 0.2, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, #TRUCK + 0.1, 0.2, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, #BUS + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #PEDESTRIAN + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] #ANIMAL From 769fe69010d9ebfe616708278ba0acbd9a3a9f68 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Fri, 11 Mar 2022 11:14:59 +0900 Subject: [PATCH 408/851] fix(detection by tracker): integration miss (#241) * fix bug Signed-off-by: Yukihiro Saito * fix bug Signed-off-by: Yukihiro Saito --- .../camera_lidar_fusion_based_detection.launch.xml | 8 ++++---- .../detection/lidar_based_detection.launch.xml | 1 + 2 files changed, 5 insertions(+), 4 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 ba7933ce68..16fa7234a7 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 @@ -34,9 +34,9 @@ --> - + - + @@ -57,7 +57,7 @@ - + @@ -120,7 +120,7 @@ - + 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 692697d6d9..579e38e8ff 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 @@ -5,6 +5,7 @@ + From 3bd7d8f6648fac323714734bc10378454f67def6 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 16 Mar 2022 20:01:51 +0900 Subject: [PATCH 409/851] fix(trajectory_follower): change stop check speed threshold to 0 (#232) Signed-off-by: Takamasa Horibe --- .../config/trajectory_follower/mpc_follower.param.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/control_launch/config/trajectory_follower/mpc_follower.param.yaml b/control_launch/config/trajectory_follower/mpc_follower.param.yaml index b3b9d60857..dcde4085b4 100644 --- a/control_launch/config/trajectory_follower/mpc_follower.param.yaml +++ b/control_launch/config/trajectory_follower/mpc_follower.param.yaml @@ -55,8 +55,8 @@ error_deriv_lpf_cutoff_hz: 5.0 # stop state - stop_state_entry_ego_speed: 0.2 - stop_state_entry_target_speed: 0.5 + stop_state_entry_ego_speed: 0.0 + stop_state_entry_target_speed: 0.0 # vehicle parameters vehicle: From 03606b33d6cf85b81b793b5d669f1667d64b1c86 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 17 Mar 2022 14:55:56 +0900 Subject: [PATCH 410/851] feat(side_shift): add parameter to configure shift request time (#226) * feat(side_shift): add parameter to configure shift request time Signed-off-by: Muhammad Zulfaqar Azmi * chore: parameter reconfigure Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_planner/side_shift/side_shift.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml index 79044041b4..815301d55a 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml @@ -6,3 +6,4 @@ shifting_lateral_jerk: 0.2 min_shifting_distance: 5.0 min_shifting_speed: 5.56 + shift_request_time_limit: 1.0 From 9809bc3c3b44ec3c474f6cb4963025f1058f7e8d Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Fri, 18 Mar 2022 10:02:46 +0900 Subject: [PATCH 411/851] fix(multi_object_tracker): data association parameter (#243) * fix(multi_object_tracker): data association parameter Signed-off-by: tomoya.kimura * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../data_association_matrix.param.yaml | 110 +++++++++--------- 1 file changed, 56 insertions(+), 54 deletions(-) diff --git a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml index 385eb335c3..6e7ac3e9ef 100644 --- a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml +++ b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml @@ -1,62 +1,64 @@ /**: ros__parameters: can_assign_matrix: - #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL - [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN - 1, 1, 1, 1, 0, 0, 0, 0, #CAR - 1, 1, 1, 1, 0, 0, 0, 0, #TRUCK - 1, 1, 1, 1, 0, 0, 0, 0, #BUS - 0, 0, 0, 0, 1, 1, 1, 0, #BICYCLE - 0, 0, 0, 0, 1, 1, 1, 0, #MOTORBIKE - 0, 0, 0, 0, 1, 1, 1, 0, #PEDESTRIAN - 0, 0, 0, 0, 0, 0, 0, 1] #ANIMAL + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE PEDESTRIAN + [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN + 1, 1, 1, 1, 1, 0, 0, 0, #CAR + 1, 1, 1, 1, 1, 0, 0, 0, #TRUCK + 1, 1, 1, 1, 1, 0, 0, 0, #BUS + 1, 1, 1, 1, 1, 0, 0, 0, #TRAILER + 0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE + 0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE + 0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN + max_dist_matrix: - #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL - [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN - 4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #CAR - 4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #TRUCK - 4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #BUS - 3.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #BICYCLE - 3.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #MOTORBIKE - 2.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #PEDESTRIAN - 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0] #ANIMAL + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN + 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR + 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK + 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS + 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER + 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #MOTORBIKE + 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #BICYCLE + 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN max_area_matrix: - #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL - [10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, #UNKNOWN - 12.10, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #CAR - 19.75, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #TRUCK - 32.40, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #BUS - 2.50, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, 10000.00, #BICYCLE - 3.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, 10000.00, #MOTORBIKE - 2.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00, 10000.00, #PEDESTRIAN - 2.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00] #ANIMAL + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, #UNKNOWN + 12.10, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #CAR + 19.75, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #TRUCK + 32.40, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #BUS + 32.40, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #TRAILER + 3.00, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #MOTORBIKE + 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #BICYCLE + 2.00, 10000.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00] #PEDESTRIAN min_area_matrix: - #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL - [ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN - 3.600, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #CAR - 6.000, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #TRUCK - 10.000, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #BUS - 0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #BICYCLE - 0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #MOTORBIKE - 0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #PEDESTRIAN - 0.500, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #ANIMAL + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN + 3.600, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #CAR + 6.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #TRUCK + 10.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #BUS + 10.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #TRAILER + 0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, #MOTORBIKE + 0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, #BICYCLE + 0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100] #PEDESTRIAN max_rad_matrix: # If value is greater than pi, it will be ignored. - #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL - [3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN - 3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #CAR - 3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #TRUCK - 3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #BUS - 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE - 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE - 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #PEDESTRIAN - 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #ANIMAL + #UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN + [3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN + min_iou_matrix: - #UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL - [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN - 0.1, 0.3, 0.2, 0.2, 0.1, 0.1, 0.1, 0.1, #CAR - 0.1, 0.2, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, #TRUCK - 0.1, 0.2, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, #BUS - 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE - 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE - 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #PEDESTRIAN - 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] #ANIMAL + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN + 0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] #PEDESTRIAN From 57df3eb25118bddfd093bda847e1da1383643f70 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 18 Mar 2022 10:17:52 +0900 Subject: [PATCH 412/851] feat(obstacle avoidance planner): update params for obstacle avoidance planner (#214) * feat(obstacle avoidance planner): update params for obstacle avoidance planner Signed-off-by: Takayuki Murooka * remove unnecessary params Signed-off-by: Takayuki Murooka * add path shape change detection for replan Signed-off-by: Takayuki Murooka * move some parameters to advanced Signed-off-by: Takayuki Murooka * calcualte radius num automatically Signed-off-by: Takayuki Murooka * tune path shape change detection Signed-off-by: Takayuki Murooka * update autoware.rviz Signed-off-by: Takayuki Murooka --- autoware_launch/rviz/autoware.rviz | 39 +-- .../obstacle_avoidance_planner.param.yaml | 251 ++++++++++++------ 2 files changed, 175 insertions(+), 115 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index c29581bd0d..b344be2e50 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1309,37 +1309,14 @@ 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_rect_location: false - current_vehicle_footprint: false - extending_constrain_rect: false - extending_constrain_rect_text: false - extending_constrain_rect_location: false - fixed_mpt_points: false - fixed_points_for_extending: false - fixed_points_marker: false - interpolated_points_for_extending: false - interpolated_points_marker: false - interpolated_points_text_marker: false - non_fixed_points_for_extending: false - non_fixed_points_marker: false - num_vehicle_footprint: false - optimized_points_marker: false - optimized_points_text_marker: false - smoothed_points_text: false - straight_points_marker: false - top_bounds_line: false - mid_bounds_line: false - vehicle_footprint: false - virtual_wall: true - virtual_wall_text: true + base_bounds_0: false + base_bounds_1: false + base_bounds_2: false + current_vehicle_circles: false + lateral_errors: false + mpt_footprints: false + vehicle_circle_lines: false + vehicle_circles: false Topic: Depth: 5 Durability Policy: Volatile diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 8150af7436..40b64b7d87 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -1,90 +1,173 @@ /**: ros__parameters: - # trajectory total/fixing length - trajectory_length: 300 # total trajectory length[m] - forward_fixing_distance: 5.0 # forward fixing length from base_link[m] - backward_fixing_distance: 3.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: 0.1 # minimum optimizing range around joint points - clearance_for_only_smoothing: 0.1 # minimum optimizing range when applying 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: 0.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_constrain_search_resolution: 1.0 # coef for fine sampling when exploring x direction - coef_y_constrain_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 + option: + # publish + is_publishing_debug_visualization_marker: true + is_publishing_clearance_map: false # publish clearance map as nav_msgs::OccupancyGrid + is_publishing_object_clearance_map: false # publish clearance map as nav_msgs::OccupancyGrid + is_publishing_area_with_objects: false # publish occupancy map as nav_msgs::OccupancyGrid + + is_stopping_if_outside_drivable_area: true # stop if the ego's footprint will be outside the drivable area + + # show + is_showing_debug_info: false + is_showing_calculation_time: false + + # other + enable_avoidance: false # enable avoidance function + enable_pre_smoothing: true # enable EB + skip_optimization: false # skip MPT and EB + reset_prev_optimization: false + + common: + # sampling + num_sampling_points: 100 # number of optimizing points + + # trajectory total/fixing length + trajectory_length: 300.0 # total trajectory length[m] + + forward_fixing_min_distance: 1.0 # number of fixing points around ego vehicle [m] + forward_fixing_min_time: 0.5 # forward fixing time with current velocity [s] + + backward_fixing_distance: 5.0 # backward fixing length from base_link [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 + + num_fix_points_for_extending: 50 # number of fixing points when extending + max_dist_for_extending_end_point: 0.0001 # minimum delta dist thres for extending last point [m] + + object: # avoiding object + max_avoiding_objects_velocity_ms: 0.5 # maximum velocity for avoiding objects [m/s] + max_avoiding_ego_velocity_ms: 6.0 # maximum ego velocity when avoiding objects [m/s] + + avoiding_object_type: + unknown: true + car: true + truck: true + bus: true + bicycle: true + motorbike: true + pedestrian: true + animal: true # mpt param - # vehicle param for mpt - max_steer_deg: 40.0 # max steering angle [deg] - steer_tau: 0.1 # steering dynamics time constant (1d approximation) [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] - forward_fixing_mpt_distance: 10 # number of fixing points around ego vehicle - - # optimization param for mpt - 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 - 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.0 # weight for steering rate - steer_acc_weight: 0.000001 # weight for steering acceleration - terminal_lat_error_weight: 0.0 # weight for lateral error at terminal point - terminal_yaw_error_weight: 100.0 # weight for yaw error at terminal point - terminal_path_lat_error_weight: 1000.0 # weight for lateral error at path end point - terminal_path_yaw_error_weight: 1000.0 # weight for yaw error at path end point - zero_ff_steer_angle: 0.5 # threshold that feed-forward angle becomes zero + mpt: + option: + steer_limit_constraint: true + fix_points_around_ego: true + # plan_from_ego: false + visualize_sampling_num: 1 + enable_manual_warm_start: true + enable_warm_start: true # false + + common: + 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] + + kinematics: + max_steer_deg: 40.0 # max steering angle [deg] + + # If this parameter is commented out, the parameter is set as below by default. + # The logic could be `optimization_center_offset = vehicle_info.wheel_base * 0.8` + # The 0.8 scale is adopted as it performed the best. + # optimization_center_offset: 2.3 # optimization center offset from base link # 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_change_detection: 2.0 # minimum delta dist thres for detecting path shape change + replan: + max_path_shape_change_dist: 0.3 # threshold of path shape change from behavior path [m] + max_ego_moving_dist_for_replan: 3.0 # threshold of ego's moving distance for replan [m] + max_delta_time_sec_for_replan: 1.0 # threshold of delta time for replan [second] + + # advanced parameters to improve performance as much as possible + advanced: + option: + # check if planned trajectory is outside drivable area + drivability_check: + # true: vehicle shape is considered as a set of circles + # false: vehicle shape is considered as footprint (= rectangle) + use_vehicle_circles: false + + # parameters only when use_vehicle_circles is true + vehicle_circles: + use_manual_vehicle_circles: false + num_for_constraints: 4 + + # parameters only when use_manual_vehicle_circles is true + longitudinal_offsets: [-0.15, 0.88, 1.9, 2.95] + radius: 0.95 + + # parameters only when use_manual_vehicle_circles is false + radius_ratio: 0.9 + # If this parameter is commented out, the parameter is calculated automatically + # based on the vehicle length and width + # num_for_radius: 4 + + eb: + common: + num_joint_buffer_points: 3 # number of joint buffer points + num_offset_for_begin_idx: 2 # number of shifting points for beginning non-fix idx + delta_arc_length_for_eb: 0.6 # 1.0 # delta arc length when optimizing[m] When the value is around 1.0, overshoot at the corner happens. + num_sampling_points_for_eb: 95 # number of optimizing points # must be longer than mpt points + + clearance: + clearance_for_straight_line: 0.05 # minimum optimizing range around straight points + clearance_for_joint: 0.1 # minimum optimizing range around joint points + clearance_for_only_smoothing: 0.1 # minimum optimizing range when applying only smoothing + + qp: + max_iteration: 10000 # max iteration when solving QP + eps_abs: 1.0e-8 # eps abs when solving OSQP + eps_rel: 1.0e-10 # eps rel when solving OSQP + + mpt: + clearance: # clearance(distance) between vehicle and roads/objects when generating trajectory + hard_clearance_from_road: 0.0 # clearance from road boundary[m] + soft_clearance_from_road: 0.1 # clearance from road boundary[m] + soft_second_clearance_from_road: 1.0 # clearance from road boundary[m] + clearance_from_object: 1.0 # clearance from object[m] + extra_desired_clearance_from_road: 0.0 # extra desired clearance from road + + weight: + soft_avoidance_weight: 1000.0 # slack weight for lateral error around the middle point + soft_second_avoidance_weight: 100.0 # slack weight for lateral error around the middle point + + lat_error_weight: 100.0 # weight for lateral error + yaw_error_weight: 0.0 # weight for yaw error + yaw_error_rate_weight: 0.0 # weight for yaw error rate + steer_input_weight: 10.0 # weight for steering input + steer_rate_weight: 10.0 # weight for steering rate + + obstacle_avoid_lat_error_weight: 3.0 # weight for lateral error + obstacle_avoid_yaw_error_weight: 0.0 # weight for yaw error + obstacle_avoid_steer_input_weight: 1000.0 # weight for yaw error + near_objects_length: 30.0 # weight for yaw error + + terminal_lat_error_weight: 100.0 # weight for lateral error at terminal point + terminal_yaw_error_weight: 100.0 # weight for yaw error at terminal point + terminal_path_lat_error_weight: 1000.0 # weight for lateral error at path end point + terminal_path_yaw_error_weight: 1000.0 # weight for yaw error at path end point + + # check if planned trajectory is outside drivable area + collision_free_constraints: + option: + l_inf_norm: true + soft_constraint: true + hard_constraint: false + # two_step_soft_constraint: false + + vehicle_circles: + use_manual_vehicle_circles: false + num_for_constraints: 3 + + # parameters only when use_manual_vehicle_circles is true + longitudinal_offsets: [-0.15, 0.88, 1.9, 2.95] + radius: 0.95 + + # parameters only when use_manual_vehicle_circles is false + radius_ratio: 0.8 + # If this parameter is commented out, the parameter is calculated automatically + # based on the vehicle length and width + # num_for_radius: 4 From ea089eaee4d68d32c666a8f52a8ce33cd6c38783 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Fri, 18 Mar 2022 11:54:54 +0900 Subject: [PATCH 413/851] feat: use extra_agg_config_file_system and register bagpacker (#242) --- .../diagnostic_aggregator/system.param.yaml | 15 +++++++++++++++ system_launch/launch/system.launch.xml | 1 + 2 files changed, 16 insertions(+) create mode 100644 system_launch/config/diagnostic_aggregator/system.param.yaml diff --git a/system_launch/config/diagnostic_aggregator/system.param.yaml b/system_launch/config/diagnostic_aggregator/system.param.yaml new file mode 100644 index 0000000000..27cbe3fed2 --- /dev/null +++ b/system_launch/config/diagnostic_aggregator/system.param.yaml @@ -0,0 +1,15 @@ +/**: + ros__parameters: + system: + type: diagnostic_aggregator/AnalyzerGroup + path: system + analyzers: + debug_data_logger: + type: diagnostic_aggregator/AnalyzerGroup + path: debug_data_logger + analyzers: + storage_error: + type: diagnostic_aggregator/GenericAnalyzer + path: storage_error + contains: ["bagpacker"] + timeout: 3.0 diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index 1292853c7e..f1986499ce 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -35,6 +35,7 @@ + From d1728be6537fe8c0e461092c24925efa1939ec32 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 18 Mar 2022 16:02:50 +0900 Subject: [PATCH 414/851] feat(planning_lanch): update autoware.rviz for debug wall marker in obstacle avoidance (#244) * update autoware.rviz for debug wall marker in obstacle avoidance Signed-off-by: Takayuki Murooka * add empty commit Signed-off-by: Takayuki Murooka --- autoware_launch/rviz/autoware.rviz | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index b344be2e50..387c582027 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1324,6 +1324,19 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: ObstacleAvoidanceWall + Namespaces: + virtual_wall: true + virtual_wall_text: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/wall_marker + Value: true Enabled: true Name: MotionPlanning Enabled: true From 0cdd76c2717de1a8920e826cf1e5f76ae3c05f7f Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 23 Mar 2022 14:23:16 +0900 Subject: [PATCH 415/851] fix(trajectory_follower): change stop check speed threshold to almost 0 (#246) Signed-off-by: Takamasa Horibe --- .../config/trajectory_follower/mpc_follower.param.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/control_launch/config/trajectory_follower/mpc_follower.param.yaml b/control_launch/config/trajectory_follower/mpc_follower.param.yaml index dcde4085b4..f8a129af4d 100644 --- a/control_launch/config/trajectory_follower/mpc_follower.param.yaml +++ b/control_launch/config/trajectory_follower/mpc_follower.param.yaml @@ -54,9 +54,9 @@ steering_lpf_cutoff_hz: 3.0 # cutoff frequency of lowpass filter for steering command [Hz] error_deriv_lpf_cutoff_hz: 5.0 - # stop state - stop_state_entry_ego_speed: 0.0 - stop_state_entry_target_speed: 0.0 + # stop state: steering command is kept in the previous value in the stop state. + stop_state_entry_ego_speed: 0.001 + stop_state_entry_target_speed: 0.001 # vehicle parameters vehicle: From b49f7e012ebc9fce5e4d83e277b9f49ff921bfd8 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 23 Mar 2022 14:54:58 +0900 Subject: [PATCH 416/851] refactor(scenario_planning.launch.xml): add parameter description (#231) Signed-off-by: Takamasa Horibe --- .../launch/scenario_planning/scenario_planning.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 82ec229d0d..5304034d27 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -23,7 +23,7 @@ - + From 329c46f8645fc5e8c527a76b851df8e0d01696b3 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 23 Mar 2022 15:14:20 +0900 Subject: [PATCH 417/851] fix(behavior_path_planner): add missing parameter (#247) Signed-off-by: Takamasa Horibe --- .../behavior_path_planner/avoidance/avoidance.param.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index 4ddd16a8f7..3e799bea13 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -45,3 +45,6 @@ # not enabled yet longitudinal_collision_margin_min_distance: 0.0 # [m] longitudinal_collision_margin_time: 0.0 + + # ---------- advanced parameters ---------- + avoidance_execution_lateral_threshold: 0.499 From a232bfa812da37e254c773cf4bafb8b0a62ca74b Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 25 Mar 2022 08:37:05 +0900 Subject: [PATCH 418/851] feat(behavior_path_planner): add configuration flag (#239) * feat(behavior_path_planner): add configuration flag The configuration flag will enable user to visualize drivable areas that have shared linestrings. This PR is related to https://github.com/autowarefoundation/autoware.universe/pull/499 Signed-off-by: Muhammad Zulfaqar Azmi * Fix: set parameter to true by default Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_planner/behavior_path_planner.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index adce0a5088..dcfedbadf7 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -16,3 +16,5 @@ refine_goal_search_radius_range: 7.5 intersection_search_distance: 30.0 + + visualize_drivable_area_for_shared_linestrings_lanelet: true From 543481dcf830bab22ce493b2bb135c5563b59b2c Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Mon, 28 Mar 2022 15:04:06 +0900 Subject: [PATCH 419/851] fix(simulator_launch): occupancy grid refer launcher file (#251) Signed-off-by: tanaka3 --- simulator_launch/launch/simulator.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index 006f35985b..06c256c367 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -50,7 +50,7 @@ - + From ae5d72a8dd862cf5d9c48a0e0d7ca8a781762fe9 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 28 Mar 2022 19:44:30 +0900 Subject: [PATCH 420/851] feat(behavior_path_planner): parametrize avoidance target type (#248) * feat(behavior_path_planner): parametrize avoidance target Signed-off-by: Takamasa Horibe * motorbike -> motorcycle Signed-off-by: Takamasa Horibe --- .../avoidance/avoidance.param.yaml | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index 3e799bea13..d691228589 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -46,5 +46,16 @@ longitudinal_collision_margin_min_distance: 0.0 # [m] longitudinal_collision_margin_time: 0.0 + # avoidance is performed for the object type with true + target_object: + car: true + truck: true + bus: true + trailer: true + unknown: false + bicycle: false + motorcycle: false + pedestrian: false + # ---------- advanced parameters ---------- avoidance_execution_lateral_threshold: 0.499 From 6d6090042f4e7336a747aea4639906b3239d102b Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 29 Mar 2022 09:21:42 +0900 Subject: [PATCH 421/851] chore: sync files (#249) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .pre-commit-config-optional.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.pre-commit-config-optional.yaml b/.pre-commit-config-optional.yaml index e54ba1fdd5..a805f1201c 100644 --- a/.pre-commit-config-optional.yaml +++ b/.pre-commit-config-optional.yaml @@ -1,6 +1,6 @@ repos: - repo: https://github.com/tcort/markdown-link-check - rev: v3.9.3 + rev: v3.10.0 hooks: - id: markdown-link-check args: [--config=.markdown-link-check.json] From 91d9d24bea0b41b02c23cefe8c4ca6e3003f4be7 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 29 Mar 2022 11:39:02 +0900 Subject: [PATCH 422/851] ci(pre-commit): update Black (#253) --- .pre-commit-config.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 0f5ae2f622..08901e6819 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -56,7 +56,7 @@ repos: - id: isort - repo: https://github.com/psf/black - rev: 22.1.0 + rev: 22.3.0 hooks: - id: black args: [--line-length=100] From 7e04bc02a6d2dbe17ea596ede6a30b17768b01b9 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Wed, 30 Mar 2022 14:07:36 +0900 Subject: [PATCH 423/851] fix(ndt_scan_matcher): fix input topic name (#254) Signed-off-by: YamatoAndo --- .../launch/pose_estimator/pose_estimator.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml index f27899050c..7e9d0ab8d2 100644 --- a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml +++ b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml @@ -3,7 +3,7 @@ - + From 8c7f5912d86795bfc7699d4d1c923fac73874e7a Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Wed, 30 Mar 2022 23:31:02 +0900 Subject: [PATCH 424/851] feat: add detected object validator (#250) * feat: add detected object validator Signed-off-by: Yukihiro Saito * bug fix Signed-off-by: Yukihiro Saito * bug fix * bug fix --- ...ra_lidar_fusion_based_detection.launch.xml | 35 ++++++++++++++++--- .../detection/detection.launch.xml | 6 ++-- .../lidar_based_detection.launch.xml | 30 ++++++++++++++-- .../launch/perception.launch.xml | 3 +- 4 files changed, 63 insertions(+), 11 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 16fa7234a7..917fd52f3a 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 @@ -17,8 +17,9 @@ - + + + + + + + + + + + + + + + @@ -85,6 +99,13 @@ + + + + + + + @@ -110,16 +131,20 @@ - + - - + + + + + + - + diff --git a/perception_launch/launch/object_recognition/detection/detection.launch.xml b/perception_launch/launch/object_recognition/detection/detection.launch.xml index 55006f9fa1..2ef5c8dab7 100644 --- a/perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -21,7 +21,7 @@ - + @@ -43,15 +43,15 @@ - + - + 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 579e38e8ff..010d7f4194 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,12 +1,26 @@ - + + + + + + + + + + + + + + + @@ -44,12 +58,24 @@ + + + + + + + + + + + - + + diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index d3d179dd37..cc09ba3a57 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -21,6 +21,7 @@ + @@ -80,7 +81,7 @@ - + From 6bb26bd086fd4d3d883a8294d6961278f68dd08e Mon Sep 17 00:00:00 2001 From: Taichi Higashide Date: Thu, 31 Mar 2022 11:34:46 +0900 Subject: [PATCH 425/851] feat: change input topic of localization and perception module to outlier_filtered/pointcloud (#215) * change localization util input topic * add arg to input arbitrary lidar topic to perception module * remove default value except autoware and logging launch * add default value in localization and perception launch * remove default value from root launch file * change input_sensor_points_topic to input/pointcloud * cosmetic change Co-authored-by: Yukihiro Saito --- autoware_launch/launch/autoware.launch.xml | 3 +-- autoware_launch/launch/logging_simulator.launch.xml | 3 +-- localization_launch/launch/localization.launch.xml | 2 ++ localization_launch/launch/util/util.launch.py | 7 +------ localization_launch/launch/util/util.launch.xml | 4 ++-- .../camera_lidar_fusion_based_detection.launch.xml | 6 +++++- .../object_recognition/detection/detection.launch.xml | 3 +++ .../detection/lidar_based_detection.launch.xml | 10 +++++++--- perception_launch/launch/perception.launch.xml | 2 ++ 9 files changed, 24 insertions(+), 16 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index e8d661bfc6..d37cf4dc64 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -50,8 +50,7 @@ - - + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 9704254fb1..dedb34b3e6 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -76,8 +76,7 @@ - - + diff --git a/localization_launch/launch/localization.launch.xml b/localization_launch/launch/localization.launch.xml index 3deae2b0e4..79851cf32a 100644 --- a/localization_launch/launch/localization.launch.xml +++ b/localization_launch/launch/localization.launch.xml @@ -1,5 +1,6 @@ + @@ -7,6 +8,7 @@ + diff --git a/localization_launch/launch/util/util.launch.py b/localization_launch/launch/util/util.launch.py index abcd824b7a..01d1e061e4 100644 --- a/localization_launch/launch/util/util.launch.py +++ b/localization_launch/launch/util/util.launch.py @@ -34,7 +34,7 @@ def load_composable_node_param(param_path): plugin="pointcloud_preprocessor::CropBoxFilterComponent", name="crop_box_filter_measurement_range", remappings=[ - ("input", LaunchConfiguration("input_sensor_points_topic")), + ("input", LaunchConfiguration("input/pointcloud")), ("output", LaunchConfiguration("output_measurement_range_sensor_points_topic")), ], parameters=[ @@ -111,11 +111,6 @@ def add_launch_arg(name: str, default_value=None, description=None): "/sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container", "container name", ) - add_launch_arg( - "input_sensor_points_topic", - "/sensing/lidar/top/rectified/pointcloud", - "input topic name for raw pointcloud", - ) add_launch_arg( "output_measurement_range_sensor_points_topic", "measurement_range/pointcloud", diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 6d2cc29549..108760f202 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -2,13 +2,13 @@ - + - + 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 917fd52f3a..72a2af0625 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 @@ -1,5 +1,6 @@ + @@ -110,6 +111,7 @@ + @@ -118,7 +120,9 @@ - + + + diff --git a/perception_launch/launch/object_recognition/detection/detection.launch.xml b/perception_launch/launch/object_recognition/detection/detection.launch.xml index 2ef5c8dab7..0fc359043d 100644 --- a/perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -1,6 +1,7 @@ + @@ -26,6 +27,7 @@ + @@ -50,6 +52,7 @@ + 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 010d7f4194..9e1e47bd8c 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,8 +1,8 @@ + - @@ -37,7 +37,9 @@ - + + + @@ -45,7 +47,9 @@ - + + + diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index cc09ba3a57..28d9aebab6 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -3,6 +3,7 @@ + @@ -64,6 +65,7 @@ + From d513999d26812c17e9e885a4df9ad9e2d28408ef Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Thu, 31 Mar 2022 15:24:27 +0900 Subject: [PATCH 426/851] feat(ndt_scan_matcher): add nearest voxel transfromation probability param (#198) * feat(ndt_scan_matcher): add nearest voxel transfromation probability param Signed-off-by: YamatoAndo * rename likelihood Signed-off-by: YamatoAndo --- localization_launch/config/ndt_scan_matcher.param.yaml | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/localization_launch/config/ndt_scan_matcher.param.yaml b/localization_launch/config/ndt_scan_matcher.param.yaml index fd21436b39..f5b454a887 100644 --- a/localization_launch/config/ndt_scan_matcher.param.yaml +++ b/localization_launch/config/ndt_scan_matcher.param.yaml @@ -23,9 +23,19 @@ # The number of iterations required to calculate alignment max_iterations: 30 + # Converged param type + # 0=TRANSFORM_PROBABILITY, 1=NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD + # NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD is only available when NDTImplementType::OMP is selected + converged_param_type: 1 + + # If converged_param_type is 0 # Threshold for deciding whether to trust the estimation result converged_param_transform_probability: 3.0 + # If converged_param_type is 1 + # Threshold for deciding whether to trust the estimation result + converged_param_nearest_voxel_transformation_likelihood: 2.3 + # The number of particles to estimate initial pose initial_estimate_particles_num: 100 From 8f9fe2539b4447b00f332bc0dae8e2cf39ccfe8e Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Thu, 31 Mar 2022 16:59:54 +0900 Subject: [PATCH 427/851] Revert "feat: change input topic of localization and perception module to outlier_filtered/pointcloud (#215)" (#256) This reverts commit 6bb26bd086fd4d3d883a8294d6961278f68dd08e. --- autoware_launch/launch/autoware.launch.xml | 3 ++- autoware_launch/launch/logging_simulator.launch.xml | 3 ++- localization_launch/launch/localization.launch.xml | 2 -- localization_launch/launch/util/util.launch.py | 7 ++++++- localization_launch/launch/util/util.launch.xml | 4 ++-- .../camera_lidar_fusion_based_detection.launch.xml | 6 +----- .../object_recognition/detection/detection.launch.xml | 3 --- .../detection/lidar_based_detection.launch.xml | 10 +++------- perception_launch/launch/perception.launch.xml | 2 -- 9 files changed, 16 insertions(+), 24 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index d37cf4dc64..e8d661bfc6 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -50,7 +50,8 @@ - + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index dedb34b3e6..9704254fb1 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -76,7 +76,8 @@ - + + diff --git a/localization_launch/launch/localization.launch.xml b/localization_launch/launch/localization.launch.xml index 79851cf32a..3deae2b0e4 100644 --- a/localization_launch/launch/localization.launch.xml +++ b/localization_launch/launch/localization.launch.xml @@ -1,6 +1,5 @@ - @@ -8,7 +7,6 @@ - diff --git a/localization_launch/launch/util/util.launch.py b/localization_launch/launch/util/util.launch.py index 01d1e061e4..abcd824b7a 100644 --- a/localization_launch/launch/util/util.launch.py +++ b/localization_launch/launch/util/util.launch.py @@ -34,7 +34,7 @@ def load_composable_node_param(param_path): plugin="pointcloud_preprocessor::CropBoxFilterComponent", name="crop_box_filter_measurement_range", remappings=[ - ("input", LaunchConfiguration("input/pointcloud")), + ("input", LaunchConfiguration("input_sensor_points_topic")), ("output", LaunchConfiguration("output_measurement_range_sensor_points_topic")), ], parameters=[ @@ -111,6 +111,11 @@ def add_launch_arg(name: str, default_value=None, description=None): "/sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container", "container name", ) + add_launch_arg( + "input_sensor_points_topic", + "/sensing/lidar/top/rectified/pointcloud", + "input topic name for raw pointcloud", + ) add_launch_arg( "output_measurement_range_sensor_points_topic", "measurement_range/pointcloud", diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 108760f202..6d2cc29549 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -2,13 +2,13 @@ - + - + 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 72a2af0625..917fd52f3a 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 @@ -1,6 +1,5 @@ - @@ -111,7 +110,6 @@ - @@ -120,9 +118,7 @@ - - - + diff --git a/perception_launch/launch/object_recognition/detection/detection.launch.xml b/perception_launch/launch/object_recognition/detection/detection.launch.xml index 0fc359043d..2ef5c8dab7 100644 --- a/perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -1,7 +1,6 @@ - @@ -27,7 +26,6 @@ - @@ -52,7 +50,6 @@ - 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 9e1e47bd8c..010d7f4194 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,8 +1,8 @@ - + @@ -37,9 +37,7 @@ - - - + @@ -47,9 +45,7 @@ - - - + diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 28d9aebab6..cc09ba3a57 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -3,7 +3,6 @@ - @@ -65,7 +64,6 @@ - From f03ef561a350259cda88c37b01fb550d49cbba08 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Fri, 1 Apr 2022 11:29:39 +0900 Subject: [PATCH 428/851] chore(behavior_velocity): make detection area off (#258) Signed-off-by: tanaka3 --- 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 387c582027..3395c11bf4 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1182,7 +1182,7 @@ Visualization Manager: collision: false info_obstacle: false obstacle: false - sidewalk: false + detection_area: false slow factor_text: true path_raw: false path_interp: false From bb0a6e937af866209b637ec9d2a774b79fdd3122 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Mon, 4 Apr 2022 20:11:48 +0900 Subject: [PATCH 429/851] feat: sync with autoware launch in awf (#255) * sync with autoware launch in awf Signed-off-by: Yukihiro Saito * call control.launch.xml as control.launch.py wrapper Signed-off-by: Takamasa Horibe * move arg for controller param file from autoware_kaunch into control_launch Signed-off-by: Takamasa Horibe * bug fix Signed-off-by: Yukihiro Saito * add launch_vehicle_interface Signed-off-by: Yukihiro Saito * bug fix Signed-off-by: Yukihiro Saito Co-authored-by: Takamasa Horibe --- autoware_launch/launch/autoware.launch.xml | 123 +++++++++++------- .../launch/logging_simulator.launch.xml | 60 ++++----- .../launch/planning_simulator.launch.xml | 107 +++++++++------ control_launch/launch/control.launch.xml | 68 ++-------- simulator_launch/launch/simulator.launch.xml | 20 ++- vehicle_launch/launch/vehicle.launch.xml | 4 +- 6 files changed, 196 insertions(+), 186 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index e8d661bfc6..a2f9a9b489 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -12,77 +12,104 @@ + - - - - + + + + + + - - - - + + + + + + + - - - - + + + + + + - - - - + + + + + + - - - - - - - + + + + + + + + + - - + + + - - - - - - + + + + + + + + - - + + + - - - - - + + + + + + - - - - - - - - + + + + + + - - + + + + + + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 9704254fb1..128f862d44 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -19,23 +19,26 @@ - + + - - - - + + + + + + @@ -43,7 +46,7 @@ - + @@ -76,8 +79,7 @@ - - + @@ -92,38 +94,38 @@ - - + - + - - - - - - - - - - - - + + + + - - - - - - + + + + + + + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 94664653c2..125b5280ad 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -20,61 +20,92 @@ + - - - - - + + + + + + + + + + - - - - + + + + + + - - - - + + + + + + - - + + + - - - - - + + + + + + - - - - + + + + + + - - + + + + - - + + + - - - - - - - - - - + + + + + + + + + + + + + + + + + diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index 9cf2f91a42..282d9e52f5 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -1,65 +1,17 @@ - - - - - - + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + - - - - diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index 06c256c367..6fa0b0e5c0 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -1,12 +1,12 @@ - + + - @@ -17,7 +17,7 @@ - + @@ -66,14 +66,12 @@ - - - - - - - - + + + + + + diff --git a/vehicle_launch/launch/vehicle.launch.xml b/vehicle_launch/launch/vehicle.launch.xml index 3ab8513d0b..24a3a19d81 100644 --- a/vehicle_launch/launch/vehicle.launch.xml +++ b/vehicle_launch/launch/vehicle.launch.xml @@ -1,9 +1,9 @@ + - @@ -19,7 +19,7 @@ - + From fcab1f7a7cbdf0e5c894f201e29869dbc574960e Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 4 Apr 2022 21:32:13 +0900 Subject: [PATCH 430/851] feat: move empty_objects_publisher (#259) Signed-off-by: tomoya.kimura --- simulator_launch/launch/simulator.launch.xml | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index 6fa0b0e5c0..aba24c3087 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -46,6 +46,14 @@ + + + + + + + + From 388c588f05cdb7e6af0b337a8197061c103f9d81 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Tue, 5 Apr 2022 10:31:46 +0900 Subject: [PATCH 431/851] fix(logging_simulator): add if for each launches (#261) --- autoware_launch/launch/logging_simulator.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 128f862d44..49be3e16ab 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -79,7 +79,7 @@ - + @@ -94,7 +94,7 @@ - + From 5df5fc6661f6fd1c93336ed841fc6981814c3935 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Tue, 5 Apr 2022 17:21:35 +0900 Subject: [PATCH 432/851] fix: run_mode (#264) --- autoware_launch/launch/planning_simulator.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 125b5280ad..8b465df955 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -40,7 +40,7 @@ - + From dc93af3504fab2d1fc50d3edc55724d277a6e051 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Tue, 5 Apr 2022 23:12:17 +0900 Subject: [PATCH 433/851] fix: rviz config in psim launch (#265) Signed-off-by: Yukihiro Saito --- autoware_launch/launch/planning_simulator.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 8b465df955..a068356779 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -82,7 +82,7 @@ exec="rviz2" name="rviz2" output="screen" - args="-d $(find-pkg-share autoware_launch)/rviz/autoware.rviz -s $(find-pkg-share autoware_launch)/rviz/image/autoware.png" + args="-d $(var rviz_config) -s $(find-pkg-share autoware_launch)/rviz/image/autoware.png" if="$(var rviz)" /> From d6f2691e626e0caa4da4531463f2804662f159ef Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 5 Apr 2022 14:40:03 +0000 Subject: [PATCH 434/851] chore: sync files (#262) * chore: sync files Signed-off-by: GitHub * ci(pre-commit): autofix Co-authored-by: kenji-miyake Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .markdownlint.yaml | 2 ++ .prettierrc.yaml | 18 ++++++++++++++++++ CPPLINT.cfg | 1 + autoware_api_launch/package.xml | 2 -- vehicle_launch/package.xml | 1 - 5 files changed, 21 insertions(+), 3 deletions(-) diff --git a/.markdownlint.yaml b/.markdownlint.yaml index dbd5b9703d..df1f518dc0 100644 --- a/.markdownlint.yaml +++ b/.markdownlint.yaml @@ -1,3 +1,4 @@ +# See https://github.com/DavidAnson/markdownlint/blob/main/doc/Rules.md for all rules. default: true MD013: false MD024: @@ -5,3 +6,4 @@ MD024: MD033: false MD041: false MD046: false +MD049: false diff --git a/.prettierrc.yaml b/.prettierrc.yaml index 48b0552e3f..e29bf32762 100644 --- a/.prettierrc.yaml +++ b/.prettierrc.yaml @@ -1,2 +1,20 @@ printWidth: 100 tabWidth: 2 +overrides: + - files: package.xml + options: + printWidth: 1000 + xmlSelfClosingSpace: false + xmlWhitespaceSensitivity: ignore + + - files: "*.launch.xml" + options: + printWidth: 200 + xmlSelfClosingSpace: false + xmlWhitespaceSensitivity: ignore + + - files: "*.xacro" + options: + printWidth: 200 + xmlSelfClosingSpace: false + xmlWhitespaceSensitivity: ignore diff --git a/CPPLINT.cfg b/CPPLINT.cfg index 1e2521f0b6..ba6bdf08c1 100644 --- a/CPPLINT.cfg +++ b/CPPLINT.cfg @@ -11,3 +11,4 @@ filter=-whitespace/parens # we allow closing parenthesis to be on the ne filter=-whitespace/semicolon # we allow the developer to decide about whitespace after a semicolon filter=-build/header_guard # we automatically fix the names of header guards using pre-commit filter=-build/include_order # we use the custom include order +filter=-build/include_subdir # we allow the style of "foo.hpp" diff --git a/autoware_api_launch/package.xml b/autoware_api_launch/package.xml index adc0e0e3a9..5777880654 100644 --- a/autoware_api_launch/package.xml +++ b/autoware_api_launch/package.xml @@ -1,7 +1,6 @@ - autoware_api_launch 0.0.0 The autoware_api_launch package @@ -22,5 +21,4 @@ ament_cmake - diff --git a/vehicle_launch/package.xml b/vehicle_launch/package.xml index cec71a23c4..c598670ac7 100644 --- a/vehicle_launch/package.xml +++ b/vehicle_launch/package.xml @@ -7,7 +7,6 @@ Yukihiro Saito Apache License 2.0 - ament_cmake_auto camera_description From 115d40938798320e263c4ec7e2d842ada9bafcb3 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 5 Apr 2022 14:53:33 +0000 Subject: [PATCH 435/851] chore: sync files (#267) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 2 +- .github/workflows/build-and-test.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 7e3d186886..51e93d5304 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -42,7 +42,7 @@ jobs: - name: Upload coverage to CodeCov if: ${{ steps.test.outputs.coverage-report-files != '' }} - uses: codecov/codecov-action@v2 + uses: codecov/codecov-action@v3 with: files: ${{ steps.test.outputs.coverage-report-files }} fail_ci_if_error: false diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 125d209ac1..a7476a607d 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -41,7 +41,7 @@ jobs: - name: Upload coverage to CodeCov if: ${{ steps.test.outputs.coverage-report-files != '' }} - uses: codecov/codecov-action@v2 + uses: codecov/codecov-action@v3 with: files: ${{ steps.test.outputs.coverage-report-files }} fail_ci_if_error: false From 98be55ead1241d7366312036f31908574f8bf529 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 5 Apr 2022 15:04:20 +0000 Subject: [PATCH 436/851] ci(pre-commit): autoupdate (#192) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * ci(pre-commit): autoupdate updates: - [github.com/igorshubovych/markdownlint-cli: v0.30.0 → v0.31.1](https://github.com/igorshubovych/markdownlint-cli/compare/v0.30.0...v0.31.1) - [github.com/pre-commit/mirrors-prettier: v2.5.1 → v2.6.2](https://github.com/pre-commit/mirrors-prettier/compare/v2.5.1...v2.6.2) - [github.com/tier4/pre-commit-hooks-ros: v0.4.0 → v0.6.0](https://github.com/tier4/pre-commit-hooks-ros/compare/v0.4.0...v0.6.0) - [github.com/shellcheck-py/shellcheck-py: v0.8.0.1 → v0.8.0.4](https://github.com/shellcheck-py/shellcheck-py/compare/v0.8.0.1...v0.8.0.4) - [github.com/scop/pre-commit-shfmt: v3.4.1-1 → v3.4.3-1](https://github.com/scop/pre-commit-shfmt/compare/v3.4.1-1...v3.4.3-1) - [github.com/pre-commit/mirrors-clang-format: v12.0.1 → v13.0.1](https://github.com/pre-commit/mirrors-clang-format/compare/v12.0.1...v13.0.1) - [github.com/cpplint/cpplint: 1.5.5 → 1.6.0](https://github.com/cpplint/cpplint/compare/1.5.5...1.6.0) * remove unnecessary clang-format and cpplint Signed-off-by: Kenji Miyake Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kenji Miyake --- .clang-format | 43 ----------------------------------------- .github/sync-files.yaml | 2 -- .pre-commit-config.yaml | 22 +++++---------------- CPPLINT.cfg | 14 -------------- 4 files changed, 5 insertions(+), 76 deletions(-) delete mode 100644 .clang-format delete mode 100644 CPPLINT.cfg diff --git a/.clang-format b/.clang-format deleted file mode 100644 index 7762ec9dfb..0000000000 --- a/.clang-format +++ /dev/null @@ -1,43 +0,0 @@ -# Modified from https://github.com/ament/ament_lint/blob/master/ament_clang_format/ament_clang_format/configuration/.clang-format -Language: Cpp -BasedOnStyle: Google - -AccessModifierOffset: -2 -AlignAfterOpenBracket: AlwaysBreak -BraceWrapping: - AfterClass: true - AfterFunction: true - AfterNamespace: true - AfterStruct: true -BreakBeforeBraces: Custom -ColumnLimit: 100 -ConstructorInitializerIndentWidth: 0 -ContinuationIndentWidth: 2 -DerivePointerAlignment: false -PointerAlignment: Middle -ReflowComments: true -IncludeCategories: - # C++ system headers - - Regex: <[a-z_]*> - Priority: 6 - CaseSensitive: true - # C system headers - - Regex: <.*\.h> - Priority: 5 - CaseSensitive: true - # Boost headers - - Regex: boost/.* - Priority: 4 - CaseSensitive: true - # Message headers - - Regex: .*_msgs/.* - Priority: 3 - CaseSensitive: true - # Other Package headers - - Regex: <.*> - Priority: 2 - CaseSensitive: true - # Local package headers - - Regex: '".*"' - Priority: 1 - CaseSensitive: true diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 34a7d476e1..7c6ac1511d 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -5,14 +5,12 @@ - source: .github/workflows/pre-commit-optional.yaml - source: .github/workflows/semantic-pull-request.yaml - source: .github/workflows/spell-check-differential.yaml - - source: .clang-format - source: .markdown-link-check.json - source: .markdownlint.yaml - source: .pre-commit-config-optional.yaml - source: .prettierignore - source: .prettierrc.yaml - source: .yamllint.yaml - - source: CPPLINT.cfg - source: setup.cfg - repository: autowarefoundation/autoware_common diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 08901e6819..4047f94b9c 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -18,13 +18,13 @@ repos: args: [--markdown-linebreak-ext=md] - repo: https://github.com/igorshubovych/markdownlint-cli - rev: v0.30.0 + rev: v0.31.1 hooks: - id: markdownlint args: [-c, .markdownlint.yaml, --fix] - repo: https://github.com/pre-commit/mirrors-prettier - rev: v2.5.1 + rev: v2.6.2 hooks: - id: prettier @@ -34,18 +34,18 @@ repos: - id: yamllint - repo: https://github.com/tier4/pre-commit-hooks-ros - rev: v0.4.0 + rev: v0.6.0 hooks: - id: prettier-package-xml - id: sort-package-xml - repo: https://github.com/shellcheck-py/shellcheck-py - rev: v0.8.0.1 + rev: v0.8.0.4 hooks: - id: shellcheck - repo: https://github.com/scop/pre-commit-shfmt - rev: v3.4.1-1 + rev: v3.4.3-1 hooks: - id: shfmt args: [-w, -s, -i=4] @@ -77,16 +77,4 @@ repos: flake8-quotes, ] - - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v12.0.1 - hooks: - - id: clang-format - - - repo: https://github.com/cpplint/cpplint - rev: 1.5.5 - hooks: - - id: cpplint - args: [--quiet] - exclude: .cu - exclude: .svg diff --git a/CPPLINT.cfg b/CPPLINT.cfg deleted file mode 100644 index ba6bdf08c1..0000000000 --- a/CPPLINT.cfg +++ /dev/null @@ -1,14 +0,0 @@ -# Modified from https://github.com/ament/ament_lint/blob/ebd524bb9973d5ec1dc48a670ce54f958a5a0243/ament_cpplint/ament_cpplint/main.py#L64-L120 -set noparent -linelength=100 -includeorder=standardcfirst -filter=-build/c++11 # we do allow C++11 -filter=-build/namespaces_literals # we allow using namespace for literals -filter=-runtime/references # we consider passing non-const references to be ok -filter=-whitespace/braces # we wrap open curly braces for namespaces, classes and functions -filter=-whitespace/indent # we don't indent keywords like public, protected and private with one space -filter=-whitespace/parens # we allow closing parenthesis to be on the next line -filter=-whitespace/semicolon # we allow the developer to decide about whitespace after a semicolon -filter=-build/header_guard # we automatically fix the names of header guards using pre-commit -filter=-build/include_order # we use the custom include order -filter=-build/include_subdir # we allow the style of "foo.hpp" From 49c95a8ea5214918c9d37605f6e50c84ff0bf1aa Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Thu, 7 Apr 2022 10:15:03 +0900 Subject: [PATCH 437/851] fix: planning simulator launch (#268) --- autoware_launch/launch/planning_simulator.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index a068356779..aa5e0e4179 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -69,8 +69,8 @@ - - + + From 228d7ed5029825298448eda74316492bf0cb60dd Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 7 Apr 2022 12:27:23 +0900 Subject: [PATCH 438/851] feat(localization_launch): change argument structure in util.launch (#270) --- .../launch/util/util.launch.py | 28 ++++++------------- .../launch/util/util.launch.xml | 13 +++++---- 2 files changed, 17 insertions(+), 24 deletions(-) diff --git a/localization_launch/launch/util/util.launch.py b/localization_launch/launch/util/util.launch.py index abcd824b7a..83d99b2a00 100644 --- a/localization_launch/launch/util/util.launch.py +++ b/localization_launch/launch/util/util.launch.py @@ -34,8 +34,8 @@ def load_composable_node_param(param_path): plugin="pointcloud_preprocessor::CropBoxFilterComponent", name="crop_box_filter_measurement_range", remappings=[ - ("input", LaunchConfiguration("input_sensor_points_topic")), - ("output", LaunchConfiguration("output_measurement_range_sensor_points_topic")), + ("input", LaunchConfiguration("input/pointcloud")), + ("output", "measurement_range/pointcloud"), ], parameters=[ load_composable_node_param("crop_box_filter_measurement_range_param_path"), @@ -47,8 +47,8 @@ def load_composable_node_param(param_path): plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", name="voxel_grid_downsample_filter", remappings=[ - ("input", LaunchConfiguration("output_measurement_range_sensor_points_topic")), - ("output", LaunchConfiguration("output_voxel_grid_downsample_sensor_points_topic")), + ("input", "measurement_range/pointcloud"), + ("output", "voxel_grid_downsample/pointcloud"), ], parameters=[load_composable_node_param("voxel_grid_downsample_filter_param_path")], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], @@ -58,8 +58,8 @@ def load_composable_node_param(param_path): plugin="pointcloud_preprocessor::RandomDownsampleFilterComponent", name="random_downsample_filter", remappings=[ - ("input", LaunchConfiguration("output_voxel_grid_downsample_sensor_points_topic")), - ("output", LaunchConfiguration("output_downsample_sensor_points_topic")), + ("input", "voxel_grid_downsample/pointcloud"), + ("output", LaunchConfiguration("output/pointcloud")), ], parameters=[load_composable_node_param("random_downsample_filter_param_path")], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], @@ -112,24 +112,14 @@ def add_launch_arg(name: str, default_value=None, description=None): "container name", ) add_launch_arg( - "input_sensor_points_topic", + "input/pointcloud", "/sensing/lidar/top/rectified/pointcloud", "input topic name for raw pointcloud", ) add_launch_arg( - "output_measurement_range_sensor_points_topic", - "measurement_range/pointcloud", - "output topic name for crop box filter", - ) - add_launch_arg( - "output_voxel_grid_downsample_sensor_points_topic", - "voxel_grid_downsample/pointcloud", - "output topic name for voxel grid downsample filter", - ) - add_launch_arg( - "output_downsample_sensor_points_topic", + "output/pointcloud", "downsample/pointcloud", - "output topic name for downsample filter. this is final output", + "final output topic name", ) return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 6d2cc29549..4973513b82 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -2,10 +2,8 @@ - - - - + + @@ -17,6 +15,11 @@ - + + + + + + From e972b1b199327be1a5be92df4f1dcbe128258a42 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Fri, 8 Apr 2022 15:02:33 +0900 Subject: [PATCH 439/851] feat: modify name of occu grid map package (#260) Signed-off-by: Yukihiro Saito --- .../launch/occupancy_grid_map/occupancy_grid_map.launch.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py b/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py index ce2a53a7f4..4225d9df20 100644 --- a/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py +++ b/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py @@ -76,8 +76,8 @@ def add_launch_arg(name: str, default_value=None): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ), ComposableNode( - package="laserscan_to_occupancy_grid_map", - plugin="occupancy_grid_map::OccupancyGridMapNode", + package="probabilistic_occupancy_grid_map", + plugin="occupancy_grid_map::LaserscanBasedOccupancyGridMapNode", name="occupancy_grid_map_node", remappings=[ ("~/input/laserscan", LaunchConfiguration("output/laserscan")), From 8342770b0c2946da364a4e3e8e36a3d164767358 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Fri, 8 Apr 2022 18:09:37 +0900 Subject: [PATCH 440/851] feat(behavior_velocity): add external velocity limit to behavior_velocity (#238) * feat(behavior_velocity): add external velocity limit to behavior_velocity Signed-off-by: tanaka3 * feat(behavior_velocity): add motion velocity smoother param to behavior velocity Signed-off-by: taikitanaka3 * fix(planning_launch): fix common param Signed-off-by: tanaka3 Co-authored-by: taikitanaka3 --- .../behavior_planning.launch.py | 40 +++++++++++++++++++ 1 file changed, 40 insertions(+) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 28971c3842..6f2c19e97d 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -178,6 +178,39 @@ def generate_launch_description(): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + # smoother param + common_param_path = os.path.join( + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "common", + "common.param.yaml", + ) + with open(common_param_path, "r") as f: + common_param = yaml.safe_load(f)["/**"]["ros__parameters"] + + base_param_path = os.path.join( + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "common", + "motion_velocity_smoother", + "motion_velocity_smoother.param.yaml", + ) + with open(base_param_path, "r") as f: + base_param = yaml.safe_load(f)["/**"]["ros__parameters"] + + smoother_param_path = os.path.join( + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "common", + "motion_velocity_smoother", + "Analytical.param.yaml", + ) + with open(smoother_param_path, "r") as f: + smoother_param = yaml.safe_load(f)["/**"]["ros__parameters"] + # behavior velocity planner blind_spot_param_path = os.path.join( get_package_share_directory("behavior_velocity_planner"), @@ -273,6 +306,10 @@ def generate_launch_description(): "~/input/external_traffic_signals", "/external/traffic_light_recognition/traffic_signals", ), + ( + "~/input/external_velocity_limit_mps", + "/planning/scenario_planning/max_velocity_default", + ), ("~/input/virtual_traffic_light_states", "/awapi/tmp/virtual_traffic_light_states"), ( "~/input/occupancy_grid", @@ -302,6 +339,9 @@ def generate_launch_description(): "max_accel": -2.8, "delay_response_time": 1.3, }, + common_param, + base_param, + smoother_param, blind_spot_param, crosswalk_param, detection_area_param, From d629633e3c9533fb54e715eca29a6c0aded56661 Mon Sep 17 00:00:00 2001 From: k-obitsu <56008637+k-obitsu@users.noreply.github.com> Date: Fri, 8 Apr 2022 23:14:12 +0900 Subject: [PATCH 441/851] fix: behavior planning launch (#271) Signed-off-by: k-obitsu --- .../blind_spot.param.yaml | 8 +++ .../crosswalk.param.yaml | 14 +++++ .../detection_area.param.yaml | 8 +++ .../intersection.param.yaml | 19 +++++++ .../no_stopping_area.param.yaml | 10 ++++ .../occlusion_spot.param.yaml | 34 ++++++++++++ .../stop_line.param.yaml | 6 +++ .../traffic_light.param.yaml | 8 +++ .../virtual_traffic_light.param.yaml | 8 +++ .../behavior_planning.launch.py | 54 +++++++++++++++---- 10 files changed, 160 insertions(+), 9 deletions(-) create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml new file mode 100644 index 0000000000..31f75d7f7c --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml @@ -0,0 +1,8 @@ +/**: + ros__parameters: + blind_spot: + use_pass_judge_line: true + stop_line_margin: 1.0 # [m] + backward_length: 15.0 # [m] + ignore_width_from_center_line: 0.7 # [m] + max_future_movement_time: 10.0 # [second] diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml new file mode 100644 index 0000000000..92e8ba6801 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml @@ -0,0 +1,14 @@ +/**: + ros__parameters: + crosswalk: + crosswalk: + stop_line_distance: 1.5 # make stop line away from crosswalk when no explicit stop line exists + stop_margin: 1.0 + slow_margin: 2.0 + slow_velocity: 2.76 # 2.76 m/s = 10.0 kmph + stop_predicted_object_prediction_time_margin: 3.0 + + walkway: + stop_line_distance: 1.5 # make stop line away from walkway when no explicit stop line exists + stop_margin: 1.0 + stop_duration_sec: 1.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml new file mode 100644 index 0000000000..9174045bf0 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml @@ -0,0 +1,8 @@ +/**: + ros__parameters: + detection_area: + stop_margin: 0.0 + use_dead_line: false + dead_line_margin: 5.0 + use_pass_judge_line: false + state_clear_time: 2.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml new file mode 100644 index 0000000000..1725a4d019 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -0,0 +1,19 @@ +/**: + ros__parameters: + intersection: + state_transit_margin_time: 0.5 + decel_velocity: 8.33 # 8.33m/s = 30.0km/h + stop_line_margin: 3.0 + stuck_vehicle_detect_dist: 3.0 # this should be the length between cars when they are stopped. The actual stuck vehicle detection length will be this value + vehicle_length. + stuck_vehicle_ignore_dist: 7.0 # obstacle stop max distance(5.0m) + stuck vehicle size / 2 (0.0m-) + stuck_vehicle_vel_thr: 0.833 # 0.833m/s = 3.0km/h + intersection_velocity: 2.778 # 2.778m/s = 10.0km/h + intersection_max_accel: 0.5 # m/ss + detection_area_margin: 0.5 # [m] + detection_area_length: 200.0 # [m] + min_predicted_path_confidence: 0.05 + collision_start_margin_time: 5.0 # [s] + collision_end_margin_time: 2.0 # [s] + + merge_from_private_road: + stop_duration_sec: 1.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml new file mode 100644 index 0000000000..32cd05a9cc --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml @@ -0,0 +1,10 @@ +/**: + ros__parameters: + no_stopping_area: + state_clear_time: 2.0 # [s] time to clear stop state + stuck_vehicle_vel_thr: 0.833 # 0.833m/s = 3.0km/h + stop_margin: 0.0 # [m] margin to stop line at no stopping area + dead_line_margin: 1.0 # [m] dead line offset go at no stopping area + stop_line_margin: 1.0 # [m] margin to auto-gen stop line at no stopping area + detection_area_length: 200.0 # [m] used to create detection area polygon + stuck_vehicle_front_margin: 6.0 # [m] obstacle stop max distance(5.0m) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml new file mode 100644 index 0000000000..1417532931 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml @@ -0,0 +1,34 @@ +/**: + ros__parameters: + occlusion_spot: + detection_method: "predicted_object" # [-] candidate is "occupancy_grid" or "predicted_object" + pass_judge: "smooth_velocity" # [-] candidate is "smooth_velocity" or "current_velocity" + filter_occupancy_grid: true # [-] whether to filter occupancy grid by morphologyEx or not + use_object_info: true # [-] whether to reflect object info to occupancy grid map or not + use_partition_lanelet: true # [-] whether to use partition lanelet map data + pedestrian_vel: 1.5 # [m/s] assume pedestrian is dashing from occlusion at this velocity + pedestrian_radius: 0.3 # [m] assume pedestrian width(0.2m) + margin(0.1m) + debug: # !Note: default should be false for performance + is_show_occlusion: false # [-] whether to show occlusion point markers. + is_show_cv_window: false # [-] whether to show open_cv debug window + is_show_processing_time: false # [-] whether to show processing time + threshold: + detection_area_length: 100.0 # [m] the length of path to consider perception range + stuck_vehicle_vel: 1.0 # [m/s] velocity below this value is assumed to stop + lateral_distance: 1.5 # [m] maximum lateral distance to consider hidden collision + motion: + safety_ratio: 0.8 # [-] jerk/acceleration ratio for safety + max_slow_down_jerk: -0.7 # [m/s^3] minimum jerk deceleration for safe brake. + max_slow_down_accel: -2.0 # [m/s^2] minimum accel deceleration for safe brake. + non_effective_jerk: -0.3 # [m/s^3] weak jerk for velocity planning. + non_effective_acceleration: -1.0 # [m/s^2] weak deceleration for velocity planning. + min_allowed_velocity: 1.0 # [m/s] minimum velocity allowed + safe_margin: 2.0 # [m] margin for detection failure(0.5m) + pedestrian radius(0.5m) + safe margin(1.0m) + detection_area: + min_occlusion_spot_size: 1.0 # [m] occupancy grid must contain an UNKNOWN area of at least size NxN to be considered a hidden obstacle. + slice_length: 10.0 # [m] size of slices in both length and distance relative to the ego path. + min_longitudinal_offset: 1.0 # [m] detection area safety buffer from front bumper. + max_lateral_distance: 6.0 # [m] buffer around the ego path used to build the detection area. + grid: + free_space_max: 40 # [-] maximum value of a free space cell in the occupancy grid + occupied_min: 60 # [-] minimum value of an occupied cell in the occupancy grid diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml new file mode 100644 index 0000000000..a2b5ac5d5f --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml @@ -0,0 +1,6 @@ +/**: + ros__parameters: + stop_line: + stop_margin: 0.0 + stop_check_dist: 2.0 + stop_duration_sec: 1.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml new file mode 100644 index 0000000000..f5db276c9e --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml @@ -0,0 +1,8 @@ +/**: + ros__parameters: + traffic_light: + stop_margin: 0.0 + tl_state_timeout: 1.0 + external_tl_state_timeout: 1.0 + yellow_lamp_period: 2.75 + enable_pass_judge: true diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml new file mode 100644 index 0000000000..267dde50c7 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml @@ -0,0 +1,8 @@ +/**: + ros__parameters: + virtual_traffic_light: + max_delay_sec: 3.0 + near_line_distance: 1.0 + dead_line_margin: 1.0 + max_yaw_deviation_deg: 90.0 + check_timeout_after_stop_line: true diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 6f2c19e97d..76c4a49e6a 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -213,72 +213,108 @@ def generate_launch_description(): # behavior velocity planner blind_spot_param_path = os.path.join( - get_package_share_directory("behavior_velocity_planner"), + get_package_share_directory("planning_launch"), "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", "blind_spot.param.yaml", ) with open(blind_spot_param_path, "r") as f: blind_spot_param = yaml.safe_load(f)["/**"]["ros__parameters"] crosswalk_param_path = os.path.join( - get_package_share_directory("behavior_velocity_planner"), + get_package_share_directory("planning_launch"), "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", "crosswalk.param.yaml", ) with open(crosswalk_param_path, "r") as f: crosswalk_param = yaml.safe_load(f)["/**"]["ros__parameters"] detection_area_param_path = os.path.join( - get_package_share_directory("behavior_velocity_planner"), + get_package_share_directory("planning_launch"), "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", "detection_area.param.yaml", ) with open(detection_area_param_path, "r") as f: detection_area_param = yaml.safe_load(f)["/**"]["ros__parameters"] intersection_param_path = os.path.join( - get_package_share_directory("behavior_velocity_planner"), + get_package_share_directory("planning_launch"), "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", "intersection.param.yaml", ) with open(intersection_param_path, "r") as f: intersection_param = yaml.safe_load(f)["/**"]["ros__parameters"] stop_line_param_path = os.path.join( - get_package_share_directory("behavior_velocity_planner"), + get_package_share_directory("planning_launch"), "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", "stop_line.param.yaml", ) with open(stop_line_param_path, "r") as f: stop_line_param = yaml.safe_load(f)["/**"]["ros__parameters"] traffic_light_param_path = os.path.join( - get_package_share_directory("behavior_velocity_planner"), + get_package_share_directory("planning_launch"), "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", "traffic_light.param.yaml", ) with open(traffic_light_param_path, "r") as f: traffic_light_param = yaml.safe_load(f)["/**"]["ros__parameters"] virtual_traffic_light_param_path = os.path.join( - get_package_share_directory("behavior_velocity_planner"), + get_package_share_directory("planning_launch"), "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", "virtual_traffic_light.param.yaml", ) with open(virtual_traffic_light_param_path, "r") as f: virtual_traffic_light_param = yaml.safe_load(f)["/**"]["ros__parameters"] occlusion_spot_param_path = os.path.join( - get_package_share_directory("behavior_velocity_planner"), + get_package_share_directory("planning_launch"), "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", "occlusion_spot.param.yaml", ) with open(occlusion_spot_param_path, "r") as f: occlusion_spot_param = yaml.safe_load(f)["/**"]["ros__parameters"] no_stopping_area_param_path = os.path.join( - get_package_share_directory("behavior_velocity_planner"), + get_package_share_directory("planning_launch"), "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", "no_stopping_area.param.yaml", ) with open(no_stopping_area_param_path, "r") as f: From 9b2c9e27f2775d81c5152d3c8bbc1abd9b47b553 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sun, 10 Apr 2022 04:45:43 +0900 Subject: [PATCH 442/851] chore: sync param files (#263) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- system_launch/config/system_monitor/cpu_monitor.param.yaml | 3 ++- system_launch/config/system_monitor/hdd_monitor.param.yaml | 3 +++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/system_launch/config/system_monitor/cpu_monitor.param.yaml b/system_launch/config/system_monitor/cpu_monitor.param.yaml index 2f049519aa..cae88d6a96 100644 --- a/system_launch/config/system_monitor/cpu_monitor.param.yaml +++ b/system_launch/config/system_monitor/cpu_monitor.param.yaml @@ -2,6 +2,7 @@ ros__parameters: usage_warn: 0.96 usage_error: 1.00 - usage_count: 2 + usage_warn_count: 2 + usage_error_count: 2 usage_avg: true msr_reader_port: 7634 diff --git a/system_launch/config/system_monitor/hdd_monitor.param.yaml b/system_launch/config/system_monitor/hdd_monitor.param.yaml index 817ff68814..70f8dc5ffa 100644 --- a/system_launch/config/system_monitor/hdd_monitor.param.yaml +++ b/system_launch/config/system_monitor/hdd_monitor.param.yaml @@ -7,5 +7,8 @@ name: / temp_warn: 55.0 temp_error: 70.0 + power_on_hours_warn: 3000000 + total_data_written_warn: 4915200 # =150TB (1unit=32MB) + total_data_written_safety_factor: 0.05 free_warn: 5120 # MB(8hour) free_error: 100 # MB(last 1 minute) From 5342092c26de582cbdbdf31dbd395b98419cd56d Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sun, 10 Apr 2022 21:10:42 +0900 Subject: [PATCH 443/851] chore: sync files (#272) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 1 + .github/workflows/build-and-test.yaml | 1 + 2 files changed, 2 insertions(+) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 51e93d5304..b77573e096 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -47,6 +47,7 @@ jobs: files: ${{ steps.test.outputs.coverage-report-files }} fail_ci_if_error: false verbose: true + flags: differential clang-tidy-differential: runs-on: ubuntu-latest diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index a7476a607d..f0760d99ae 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -46,3 +46,4 @@ jobs: files: ${{ steps.test.outputs.coverage-report-files }} fail_ci_if_error: false verbose: true + flags: total From 199941b7a1fa98df6d09a53bf4d8de1f80f3bb72 Mon Sep 17 00:00:00 2001 From: Taichi Higashide Date: Mon, 11 Apr 2022 17:38:20 +0900 Subject: [PATCH 444/851] feat: change input pointcloud from outside of launch file (#257) * change localization util input topic * add arg to input arbitrary lidar topic to perception module * remove default value except autoware and logging launch * add default value in localization and perception launch * remove default value from root launch file * change input_sensor_points_topic to input/pointcloud * cosmetic change * feat: use pointcloud container * feat: move into util * ci(pre-commit): autofix * feat: make final output topic arg * fix: typo * fix: some lack things * fix: revert use pointcloud container * change to work tutorial Signed-off-by: Yukihiro Saito * change to work tutorial Signed-off-by: Yukihiro Saito Co-authored-by: Yukihiro Saito Co-authored-by: h-ohta Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../launch/localization.launch.xml | 5 +++++ localization_launch/launch/util/util.launch.py | 11 +---------- localization_launch/launch/util/util.launch.xml | 9 ++------- ...mera_lidar_fusion_based_detection.launch.xml | 14 +++++++++----- .../detection/detection.launch.xml | 3 +++ .../detection/lidar_based_detection.launch.xml | 17 +++++++++++------ perception_launch/launch/perception.launch.xml | 2 ++ 7 files changed, 33 insertions(+), 28 deletions(-) diff --git a/localization_launch/launch/localization.launch.xml b/localization_launch/launch/localization.launch.xml index 3deae2b0e4..20b29e5afe 100644 --- a/localization_launch/launch/localization.launch.xml +++ b/localization_launch/launch/localization.launch.xml @@ -1,5 +1,8 @@ + + + @@ -7,6 +10,8 @@ + + diff --git a/localization_launch/launch/util/util.launch.py b/localization_launch/launch/util/util.launch.py index 83d99b2a00..1721ec7d7b 100644 --- a/localization_launch/launch/util/util.launch.py +++ b/localization_launch/launch/util/util.launch.py @@ -106,16 +106,7 @@ def add_launch_arg(name: str, default_value=None, description=None): "path to the parameter file of random_downsample_filter", ) add_launch_arg("use_intra_process", "true", "use ROS2 component container communication") - add_launch_arg( - "container", - "/sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container", - "container name", - ) - add_launch_arg( - "input/pointcloud", - "/sensing/lidar/top/rectified/pointcloud", - "input topic name for raw pointcloud", - ) + add_launch_arg( "output/pointcloud", "downsample/pointcloud", diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 4973513b82..4b80a343da 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -1,14 +1,9 @@ - - + - - - - - + 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 917fd52f3a..c661c15a1e 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 @@ -1,5 +1,7 @@ + + @@ -19,7 +21,6 @@ - - + @@ -47,7 +48,7 @@ - + @@ -110,6 +111,7 @@ + @@ -118,7 +120,9 @@ - + + + @@ -134,7 +138,7 @@ - + diff --git a/perception_launch/launch/object_recognition/detection/detection.launch.xml b/perception_launch/launch/object_recognition/detection/detection.launch.xml index 2ef5c8dab7..0fc359043d 100644 --- a/perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -1,6 +1,7 @@ + @@ -26,6 +27,7 @@ + @@ -50,6 +52,7 @@ + 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 010d7f4194..e32dcac20b 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,13 +1,14 @@ + + - - + @@ -18,7 +19,7 @@ - + @@ -37,7 +38,9 @@ - + + + @@ -45,7 +48,9 @@ - + + + @@ -61,7 +66,7 @@ - + diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index cc09ba3a57..1b6d3581bf 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -2,6 +2,7 @@ + @@ -64,6 +65,7 @@ + From 87bad257cc9a2c4093ad9257bc84fc3ab33f8b7c Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 12 Apr 2022 09:44:22 +0900 Subject: [PATCH 445/851] ci(pre-commit): autoupdate (#276) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit updates: - [github.com/pre-commit/pre-commit-hooks: v4.1.0 → v4.2.0](https://github.com/pre-commit/pre-commit-hooks/compare/v4.1.0...v4.2.0) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .pre-commit-config.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 4047f94b9c..6248132b9f 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -4,7 +4,7 @@ ci: repos: - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.1.0 + rev: v4.2.0 hooks: - id: check-json - id: check-merge-conflict From 6df3123820f4424a95d610cdc11116eb1e54b2a0 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 12 Apr 2022 11:05:52 +0900 Subject: [PATCH 446/851] feat(planning_launch): add scenario topic remap in behavior launch (#275) Signed-off-by: Takamasa Horibe --- .../lane_driving/behavior_planning/behavior_planning.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 76c4a49e6a..8e2fe26291 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -130,6 +130,7 @@ def generate_launch_description(): ("~/input/vector_map", LaunchConfiguration("map_topic_name")), ("~/input/perception", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), + ("~/input/scenario", "/planning/scenario_planning/scenario"), ( "~/input/external_approval", "/planning/scenario_planning/lane_driving/behavior_planning/" From 2811d73ff66d7c1a4594c71fb04faf600ac8948c Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 12 Apr 2022 03:12:11 +0000 Subject: [PATCH 447/851] chore: sync files (#278) * chore: sync files Signed-off-by: GitHub * Update sync-files.yaml Co-authored-by: kenji-miyake Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .github/sync-files.yaml | 2 +- .github/workflows/sync-files.yaml | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 7c6ac1511d..bb0f7f3b10 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -5,6 +5,7 @@ - source: .github/workflows/pre-commit-optional.yaml - source: .github/workflows/semantic-pull-request.yaml - source: .github/workflows/spell-check-differential.yaml + - source: .github/workflows/sync-files.yaml - source: .markdown-link-check.json - source: .markdownlint.yaml - source: .pre-commit-config-optional.yaml @@ -17,4 +18,3 @@ files: - source: .github/workflows/build-and-test.yaml - source: .github/workflows/build-and-test-differential.yaml - - source: .github/workflows/sync-files.yaml diff --git a/.github/workflows/sync-files.yaml b/.github/workflows/sync-files.yaml index 32f4613f6d..5dfe195c06 100644 --- a/.github/workflows/sync-files.yaml +++ b/.github/workflows/sync-files.yaml @@ -20,3 +20,4 @@ jobs: uses: autowarefoundation/autoware-github-actions/sync-files@v1 with: token: ${{ steps.generate-token.outputs.token }} + auto-merge-method: squash From fbadee526c351db1e4929ffa119cc7b7c2c6deba Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Wed, 13 Apr 2022 12:13:27 +0900 Subject: [PATCH 448/851] ci: add labels to PRs submitted by a bot (#279) Signed-off-by: Kenji Miyake --- .github/dependabot.yaml | 3 +++ .github/workflows/sync-files.yaml | 3 +++ .github/workflows/sync-upstream.yaml | 3 +++ 3 files changed, 9 insertions(+) diff --git a/.github/dependabot.yaml b/.github/dependabot.yaml index 9a2fbd7542..3f3bf243f6 100644 --- a/.github/dependabot.yaml +++ b/.github/dependabot.yaml @@ -5,3 +5,6 @@ updates: schedule: interval: daily open-pull-requests-limit: 1 + labels: + - bot + - github-actions diff --git a/.github/workflows/sync-files.yaml b/.github/workflows/sync-files.yaml index 5dfe195c06..69ef19c684 100644 --- a/.github/workflows/sync-files.yaml +++ b/.github/workflows/sync-files.yaml @@ -20,4 +20,7 @@ jobs: uses: autowarefoundation/autoware-github-actions/sync-files@v1 with: token: ${{ steps.generate-token.outputs.token }} + pr-labels: | + bot + sync-files auto-merge-method: squash diff --git a/.github/workflows/sync-upstream.yaml b/.github/workflows/sync-upstream.yaml index 68a0315fed..66eb180976 100644 --- a/.github/workflows/sync-upstream.yaml +++ b/.github/workflows/sync-upstream.yaml @@ -25,4 +25,7 @@ jobs: sync-target-repository: https://github.com/tier4/autoware_launch.git sync-target-branch: tier4/universe pr-title: "chore: sync upstream" + pr-labels: | + bot + sync-upstream auto-merge-method: merge From 57fd34955f5fb94a94b2d7d5045aecdedbc7b3e5 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 13 Apr 2022 15:42:01 +0900 Subject: [PATCH 449/851] feat: add drivable area boundary to the autoware.rviz (#269) Signed-off-by: Muhammad Zulfaqar Azmi --- autoware_launch/rviz/autoware.rviz | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 3395c11bf4..149b056117 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1235,6 +1235,18 @@ Visualization Manager: Constant Color: false Scale: 0.30000001192092896 Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: DrivableAreaBoundary + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_boundary + Value: true Enabled: true Name: BehaviorPlanning - Class: rviz_common/Group From 896dbc86ed05d792cdc073316bc952e0cfb26050 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Wed, 13 Apr 2022 18:05:23 +0900 Subject: [PATCH 450/851] feat(rviz): add trajectory error marker (#281) Signed-off-by: tanaka3 --- autoware_launch/rviz/autoware.rviz | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 149b056117..1b924cc6c3 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1417,6 +1417,22 @@ Visualization Manager: Value: true Enabled: true Name: Parking + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: TrajectoryErrorMarker + Namespaces: + trajectory_relative_angle: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/planning_diagnostics/planning_error_monitor/debug/marker + Value: true + Enabled: true + Name: PlanningDiagnostics Enabled: true Name: ScenarioPlanning Enabled: true From 52e9c2489e0335d77b082cedce4beaefc7ed6381 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Thu, 14 Apr 2022 14:12:46 +0900 Subject: [PATCH 451/851] feat(behavior_velocity): use occlusion spot (#282) * feat(behavior_velocity): use occupancy grid method Signed-off-by: tanaka3 * chore(behavior_velocity): update to experiment value Signed-off-by: tanaka3 --- .../behavior_velocity_planner/occlusion_spot.param.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml index 1417532931..a2f16ee825 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml @@ -1,8 +1,8 @@ /**: ros__parameters: occlusion_spot: - detection_method: "predicted_object" # [-] candidate is "occupancy_grid" or "predicted_object" - pass_judge: "smooth_velocity" # [-] candidate is "smooth_velocity" or "current_velocity" + detection_method: "occupancy_grid" # [-] candidate is "occupancy_grid" or "predicted_object" + pass_judge: "smooth_velocity" # [-] candidate is "smooth_velocity" or "current_velocity" filter_occupancy_grid: true # [-] whether to filter occupancy grid by morphologyEx or not use_object_info: true # [-] whether to reflect object info to occupancy grid map or not use_partition_lanelet: true # [-] whether to use partition lanelet map data @@ -18,8 +18,8 @@ lateral_distance: 1.5 # [m] maximum lateral distance to consider hidden collision motion: safety_ratio: 0.8 # [-] jerk/acceleration ratio for safety - max_slow_down_jerk: -0.7 # [m/s^3] minimum jerk deceleration for safe brake. - max_slow_down_accel: -2.0 # [m/s^2] minimum accel deceleration for safe brake. + max_slow_down_jerk: -0.5 # [m/s^3] minimum jerk deceleration for safe brake. + max_slow_down_accel: -1.8 # [m/s^2] minimum accel deceleration for safe brake. non_effective_jerk: -0.3 # [m/s^3] weak jerk for velocity planning. non_effective_acceleration: -1.0 # [m/s^2] weak deceleration for velocity planning. min_allowed_velocity: 1.0 # [m/s] minimum velocity allowed From 8bd0cbf19a76a63fbd986c128e9c3211cb1eb27a Mon Sep 17 00:00:00 2001 From: Yusuke Muramatsu Date: Thu, 14 Apr 2022 16:01:47 +0900 Subject: [PATCH 452/851] feat: replace roi_cluster_fusion to image_projection_based_fusion (#274) Signed-off-by: yukke42 --- .../detection/camera_lidar_fusion_based_detection.launch.xml | 4 ++-- perception_launch/package.xml | 2 +- 2 files changed, 3 insertions(+), 3 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 c661c15a1e..b0bf3263dc 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 @@ -54,7 +54,7 @@ - + @@ -81,7 +81,7 @@ - + diff --git a/perception_launch/package.xml b/perception_launch/package.xml index bf643b5c10..4c5673c04f 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -13,6 +13,7 @@ compare_map_segmentation euclidean_cluster ground_segmentation + image_projection_based_fusion image_transport_decompressor lidar_apollo_instance_segmentation map_based_prediction @@ -22,7 +23,6 @@ occupancy_grid_map_outlier_filter pointcloud_preprocessor pointcloud_to_laserscan - roi_cluster_fusion shape_estimation tensorrt_yolo traffic_light_classifier From d5019f43bf06a18e1d4c5dd85df3d98b36b7293a Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 14 Apr 2022 17:39:32 +0900 Subject: [PATCH 453/851] feat: add raw twist output from gyro_odometer (#277) Signed-off-by: kminoda --- .../launch/twist_estimator/twist_estimator.launch.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml index 76d0a73dbc..fd7854a7e4 100644 --- a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml +++ b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml @@ -7,5 +7,6 @@ + From 7a9ad30407e8c780ee1b5d2175d79d360a94dfdc Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sun, 17 Apr 2022 10:02:28 +0900 Subject: [PATCH 454/851] chore: sync files (#284) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/pre-commit.yaml | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml index e1b72f7068..7fd1cc90fe 100644 --- a/.github/workflows/pre-commit.yaml +++ b/.github/workflows/pre-commit.yaml @@ -5,12 +5,28 @@ on: jobs: pre-commit: + if: ${{ github.event.repository.private }} runs-on: ubuntu-latest steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + - name: Check out repository uses: actions/checkout@v3 + with: + ref: ${{ github.event.pull_request.head.ref }} + + - name: Set git config + uses: autowarefoundation/autoware-github-actions/set-git-config@v1 + with: + token: ${{ steps.generate-token.outputs.token }} - name: Run pre-commit uses: autowarefoundation/autoware-github-actions/pre-commit@v1 with: pre-commit-config: .pre-commit-config.yaml + token: ${{ steps.generate-token.outputs.token }} From 5bfee4cfd8e5c77dbb44a2421e8cd0d0b54e7d01 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Tue, 19 Apr 2022 12:39:42 +0900 Subject: [PATCH 455/851] feat: use same parameter for system_error_monitor (#252) * feat: use same parameter for system_error_monitor * feat: launch when run_mode is psim * feat: launch system_monitor only in online * feat: crete launch.py * ci(pre-commit): autofix * fix: delete print * feat: create dummy.param.yaml * feat: make multi dummy diag publisher.launch.xml for each functions * feat: add include for sensor_kit Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- ...ror_monitor.planning_simulation.param.yaml | 50 ---------- .../dummy_diag_publisher/control.launch.xml | 7 ++ .../localization.launch.xml | 11 +++ .../dummy_diag_publisher/system.launch.xml | 91 +++++++++++++++++++ .../dummy_diag_publisher/vehicle.launch.xml | 7 ++ system_launch/launch/system.launch.xml | 15 ++- 6 files changed, 128 insertions(+), 53 deletions(-) delete mode 100644 system_launch/config/system_error_monitor.planning_simulation.param.yaml create mode 100644 system_launch/launch/dummy_diag_publisher/control.launch.xml create mode 100644 system_launch/launch/dummy_diag_publisher/localization.launch.xml create mode 100644 system_launch/launch/dummy_diag_publisher/system.launch.xml create mode 100644 system_launch/launch/dummy_diag_publisher/vehicle.launch.xml diff --git a/system_launch/config/system_error_monitor.planning_simulation.param.yaml b/system_launch/config/system_error_monitor.planning_simulation.param.yaml deleted file mode 100644 index ce081b75b2..0000000000 --- a/system_launch/config/system_error_monitor.planning_simulation.param.yaml +++ /dev/null @@ -1,50 +0,0 @@ -# Description: -# name: diag name -# sf_at: diag level where it becomes Safe Fault -# lf_at: diag level where it becomes Latent Fault -# spf_at: diag level where it becomes Single Point Fault -# auto_recovery: Determines whether the system will automatically recover when it recovers from an error. -# -# Note: -# empty-value for sf_at, lf_at and spf_at is "none" -# default values are: -# sf_at: "none" -# lf_at: "warn" -# spf_at: "error" -# auto_recovery: "true" ---- -/**: - ros__parameters: - required_modules: - autonomous_driving: - /autoware/control/autonomous_driving/node_alive_monitoring: default - /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default - /autoware/control/control_command_gate/node_alive_monitoring: default - - /autoware/localization/node_alive_monitoring: default - # /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } - # /autoware/localization/performance_monitoring/localization_accuracy: default - - /autoware/map/node_alive_monitoring: default - - /autoware/perception/node_alive_monitoring: default - - /autoware/planning/node_alive_monitoring: default - /autoware/planning/performance_monitoring/trajectory_validation: default - - /autoware/sensing/node_alive_monitoring: default - - /autoware/system/node_alive_monitoring: default - /autoware/system/emergency_stop_operation: default - # /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "error", spf_at: "none" } - - /autoware/vehicle/node_alive_monitoring: default - - external_control: - /autoware/control/control_command_gate/node_alive_monitoring: default - /autoware/control/external_control/external_command_selector/node_alive_monitoring: default - - /autoware/system/node_alive_monitoring: default - /autoware/system/emergency_stop_operation: default - - /autoware/vehicle/node_alive_monitoring: default diff --git a/system_launch/launch/dummy_diag_publisher/control.launch.xml b/system_launch/launch/dummy_diag_publisher/control.launch.xml new file mode 100644 index 0000000000..b93a93d927 --- /dev/null +++ b/system_launch/launch/dummy_diag_publisher/control.launch.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/system_launch/launch/dummy_diag_publisher/localization.launch.xml b/system_launch/launch/dummy_diag_publisher/localization.launch.xml new file mode 100644 index 0000000000..19f70a723d --- /dev/null +++ b/system_launch/launch/dummy_diag_publisher/localization.launch.xml @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/system_launch/launch/dummy_diag_publisher/system.launch.xml b/system_launch/launch/dummy_diag_publisher/system.launch.xml new file mode 100644 index 0000000000..164dfe2e12 --- /dev/null +++ b/system_launch/launch/dummy_diag_publisher/system.launch.xml @@ -0,0 +1,91 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/system_launch/launch/dummy_diag_publisher/vehicle.launch.xml b/system_launch/launch/dummy_diag_publisher/vehicle.launch.xml new file mode 100644 index 0000000000..3848c9e7e9 --- /dev/null +++ b/system_launch/launch/dummy_diag_publisher/vehicle.launch.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index f1986499ce..88aaca8527 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -9,7 +9,7 @@ - + @@ -30,8 +30,7 @@ - - + @@ -45,5 +44,15 @@ + + + + + + + + + + From 8b4f7da7d9917cdb9fed26017dd52500e0875f1b Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Wed, 20 Apr 2022 16:52:23 +0900 Subject: [PATCH 456/851] feat: change ogm default launch (#287) Signed-off-by: Yukihiro Saito --- ...erscan_based_occupancy_grid_map.launch.py} | 2 +- ...ntcloud_based_occupancy_grid_map.launch.py | 93 +++++++++++++++++++ .../launch/perception.launch.xml | 2 +- 3 files changed, 95 insertions(+), 2 deletions(-) rename perception_launch/launch/occupancy_grid_map/{occupancy_grid_map.launch.py => laserscan_based_occupancy_grid_map.launch.py} (98%) create mode 100644 perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py diff --git a/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py b/perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py similarity index 98% rename from perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py rename to perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py index 4225d9df20..d371fa4398 100644 --- a/perception_launch/launch/occupancy_grid_map/occupancy_grid_map.launch.py +++ b/perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py @@ -59,7 +59,7 @@ def add_launch_arg(name: str, default_value=None): "max_height": 2.0, "angle_min": -3.141592, # -M_PI "angle_max": 3.141592, # M_PI - "angle_increment": 0.0034906585, # 0.20*M_PI/180.0 + "angle_increment": 0.00349065850, # 0.20*M_PI/180.0 "scan_time": 0.0, "range_min": 1.0, "range_max": 200.0, diff --git a/perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py b/perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py new file mode 100644 index 0000000000..2b7f9f8e83 --- /dev/null +++ b/perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py @@ -0,0 +1,93 @@ +# Copyright 2021 Tier IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import LaunchConfigurationEquals +from launch.conditions import LaunchConfigurationNotEquals +from launch.conditions import UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes +from launch_ros.descriptions import ComposableNode + + +def generate_launch_description(): + def add_launch_arg(name: str, default_value=None): + return DeclareLaunchArgument(name, default_value=default_value) + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + + composable_nodes = [ + ComposableNode( + package="probabilistic_occupancy_grid_map", + plugin="occupancy_grid_map::PointcloudBasedOccupancyGridMapNode", + name="occupancy_grid_map_node", + remappings=[ + ("~/input/obstacle_pointcloud", LaunchConfiguration("input/obstacle_pointcloud")), + ("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")), + ("~/output/occupancy_grid_map", LaunchConfiguration("output")), + ], + parameters=[ + { + "map_resolution": 0.5, + "use_height_filter": True, + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ), + ] + + occupancy_grid_map_container = ComposableNodeContainer( + condition=LaunchConfigurationEquals("container", ""), + name="occupancy_grid_map_container", + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=composable_nodes, + output="screen", + ) + + load_composable_nodes = LoadComposableNodes( + condition=LaunchConfigurationNotEquals("container", ""), + composable_node_descriptions=composable_nodes, + target_container=LaunchConfiguration("container"), + ) + + return LaunchDescription( + [ + add_launch_arg("container", ""), + add_launch_arg("use_multithread", "false"), + add_launch_arg("use_intra_process", "false"), + add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"), + add_launch_arg("input/raw_pointcloud", "concatenated/pointcloud"), + add_launch_arg("output", "occupancy_grid"), + set_container_executable, + set_container_mt_executable, + occupancy_grid_map_container, + load_composable_nodes, + ] + ) diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 1b6d3581bf..5b652bac5c 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -46,7 +46,7 @@ - + From ca554454434451a495baa22e80e51f2adfd46477 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Wed, 20 Apr 2022 18:02:44 +0900 Subject: [PATCH 457/851] feat(simulator_launch): add fault_injection config (#286) Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> --- simulator_launch/CMakeLists.txt | 1 + .../config/fault_injection.param.yaml | 37 +++++++++++++++++++ simulator_launch/launch/simulator.launch.xml | 4 +- 3 files changed, 41 insertions(+), 1 deletion(-) create mode 100644 simulator_launch/config/fault_injection.param.yaml diff --git a/simulator_launch/CMakeLists.txt b/simulator_launch/CMakeLists.txt index bbabec7ab1..05e5c27e2b 100644 --- a/simulator_launch/CMakeLists.txt +++ b/simulator_launch/CMakeLists.txt @@ -11,4 +11,5 @@ endif() ament_auto_package(INSTALL_TO_SHARE launch + config ) diff --git a/simulator_launch/config/fault_injection.param.yaml b/simulator_launch/config/fault_injection.param.yaml new file mode 100644 index 0000000000..1a57b852f7 --- /dev/null +++ b/simulator_launch/config/fault_injection.param.yaml @@ -0,0 +1,37 @@ +/**: + ros__parameters: + event_diag_list: + vehicle_is_out_of_lane: "lane_departure" + trajectory_deviation_is_high: "trajectory_deviation" + localization_matching_score_is_low: "ndt_scan_matcher" + localization_accuracy_is_low: "localization_accuracy" + map_version_is_different: "map_version" + trajectory_is_invalid: "trajectory_point_validation" + cpu_temperature_is_high: "CPU Temperature" + cpu_usage_is_high: "CPU Usage" + cpu_is_in_thermal_throttling: "CPU Thermal Throttling" + storage_temperature_is_high: "HDD Temperature" + storage_usage_is_high: "HDD Usage" + network_usage_is_high: "Network Usage" + clock_error_is_large: "NTP Offset" + gpu_temperature_is_high: "GPU Temperature" + gpu_usage_is_high: "GPU Usage" + gpu_memory_usage_is_high: "GPU Memory Usage" + gpu_is_in_thermal_throttling: "GPU Thermal Throttling" + driving_recorder_storage_error: "driving_recorder" + debug_data_logger_storage_error: "bagpacker" + emergency_stop_operation: "emergency_stop_operation" + vehicle_error_occurred: "vehicle_errors" + vehicle_ecu_connection_is_lost: "can_bus_connection" + obstacle_crash_sensor_is_activated: "obstacle_crash" + /control/command_gate/node_alive_monitoring: "vehicle_cmd_gate: heartbeat" + /control/autonomous_driving/node_alive_monitoring: "control_topic_status" + /control/external_command_selector/node_alive_monitoring: "external_cmd_selector: heartbeat" + /localization/node_alive_monitoring: "localization_topic_status" + /map/node_alive_monitoring: "map_topic_status" + /planning/node_alive_monitoring: "planning_topic_status" + /sensing/lidar/node_alive_monitoring: "lidar_topic_status" + /sensing/imu/node_alive_monitoring: "imu_connection" + /sensing/gnss/node_alive_monitoring: "gnss_connection" + /system/node_alive_monitoring: "system_topic_status" + /vehicle/node_alive_monitoring: "vehicle_topic_status" diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index aba24c3087..8a0950b90a 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -13,7 +13,9 @@ - + + + From 653bafe42cb2ca124ef7fd038c8106aa107ebebc Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Thu, 21 Apr 2022 01:16:48 +0900 Subject: [PATCH 458/851] fix: ogm launch in psim (#288) * fix: ogm launch in psim * Update simulator.launch.xml * Update simulator.launch.xml --- simulator_launch/launch/simulator.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index 8a0950b90a..f66519d58f 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -60,7 +60,7 @@ - + From 7c33edd3c8054e901abdb187ca25248ec27b0f43 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 21 Apr 2022 12:07:17 +0900 Subject: [PATCH 459/851] fix(motion_velocity_smoother): add stop decel parameter (#289) * add stop decel parameter * fix(motion_velocity_smoother): add stop decel parameter --- .../motion_velocity_smoother/motion_velocity_smoother.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index db13e491b1..adffe53472 100644 --- a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -2,6 +2,7 @@ ros__parameters: # motion state constraints max_velocity: 20.0 # max velocity limit [m/s] + stop_decel: 0.0 # deceleration at a stop point[m/ss] # external velocity limit parameter margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m] From 8fc641a277ed7945bdc80d5a59292922050c70e2 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 21 Apr 2022 13:49:05 +0900 Subject: [PATCH 460/851] fix(control_launch): add parameter of entry condition for STOPPED STATE (#283) --- .../trajectory_follower/longitudinal_controller.param.yaml | 1 + .../config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml | 1 + 2 files changed, 2 insertions(+) diff --git a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml index 97fad61fac..3c9d79c8f7 100644 --- a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml +++ b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml @@ -11,6 +11,7 @@ drive_state_stop_dist: 0.5 drive_state_offset_stop_dist: 1.0 stopping_state_stop_dist: 0.5 + stopped_state_entry_duration_time: 0.1 stopped_state_entry_vel: 0.01 stopped_state_entry_acc: 0.1 emergency_state_overshoot_stop_dist: 1.5 diff --git a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml b/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml index 94b682a6b4..0ad4631c6d 100644 --- a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml +++ b/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml @@ -5,6 +5,7 @@ external_emergency_stop_heartbeat_timeout: 0.0 stop_hold_acceleration: -1.5 emergency_acceleration: -2.4 + stopped_state_entry_duration_time: 0.1 vel_lim: 25.0 lon_acc_lim: 5.0 lon_jerk_lim: 5.0 From 2d5b7b2199f0eeb3bfd00339be6804db6923e33c Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Sat, 23 Apr 2022 11:29:17 +0900 Subject: [PATCH 461/851] ci(sync-files): sync github-release.yaml (#291) Signed-off-by: Kenji Miyake --- .github/sync-files.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index bb0f7f3b10..181be61423 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -1,6 +1,7 @@ - repository: autowarefoundation/autoware files: - source: .github/dependabot.yaml + - source: .github/workflows/github-release.yaml - source: .github/workflows/pre-commit.yaml - source: .github/workflows/pre-commit-optional.yaml - source: .github/workflows/semantic-pull-request.yaml From fb80eb499220411cc1e92cdb7e20964198d5ecfa Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sat, 23 Apr 2022 02:34:46 +0000 Subject: [PATCH 462/851] chore: sync files (#292) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/github-release.yaml | 63 +++++++++++++++++++++++++++ 1 file changed, 63 insertions(+) create mode 100644 .github/workflows/github-release.yaml diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml new file mode 100644 index 0000000000..7bb9d70931 --- /dev/null +++ b/.github/workflows/github-release.yaml @@ -0,0 +1,63 @@ +name: github-release + +on: + push: + branches: + - beta/v* + tags: + - v* + workflow_dispatch: + inputs: + beta-branch-or-tag-name: + type: string + required: true + +jobs: + github-release: + runs-on: ubuntu-latest + steps: + - name: Set tag name + id: set-tag-name + run: | + if [ "${{ github.event_name }}" = "workflow_dispatch" ]; then + REF_NAME="${{ github.event.inputs.beta-branch-or-tag-name }}" + else + REF_NAME="${{ github.ref_name }}" + fi + + echo ::set-output name=ref-name::"$REF_NAME" + echo ::set-output name=tag-name::"${REF_NAME#beta/}" + + - name: Check out repository + uses: actions/checkout@v3 + with: + fetch-depth: 0 + ref: ${{ steps.set-tag-name.outputs.ref-name }} + + - name: Set target name for beta branches + id: set-target-name + run: | + if [[ "${{ steps.set-tag-name.outputs.ref-name }}" =~ "beta/" ]]; then + echo ::set-output name=target-name::"${{ steps.set-tag-name.outputs.ref-name }}" + fi + + - name: Create a local tag for beta branches + run: | + if [ "${{ steps.set-target-name.outputs.target-name }}" != "" ]; then + git tag "${{ steps.set-tag-name.outputs.tag-name }}" + fi + + - name: Run generate-changelog + id: generate-changelog + uses: autowarefoundation/autoware-github-actions/generate-changelog@v1 + + - name: Release to GitHub + run: | + gh release create "${{ steps.set-tag-name.outputs.tag-name }}" \ + --draft \ + --target "${{ steps.set-target-name.outputs.target-name }}" \ + --title "Release ${{ steps.set-tag-name.outputs.tag-name }}" \ + --notes "$NOTES" + env: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} + NOTES: ${{ steps.generate-changelog.outputs.changelog }} From b2c2528d6c5a8d5a43b90ea9c493151ec9453853 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Sat, 23 Apr 2022 11:37:41 +0900 Subject: [PATCH 463/851] fix(occulusion_spot): fix spell check failure (#290) --- 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 1b924cc6c3..28bed4d2e8 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1185,7 +1185,7 @@ Visualization Manager: detection_area: false slow factor_text: true path_raw: false - path_interp: false + path_interpolated: false Topic: Depth: 5 Durability Policy: Volatile From 02e5e34fff8589a75888509ce6edf2434fb01379 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Mon, 25 Apr 2022 09:33:44 +0900 Subject: [PATCH 464/851] fix(map_launch): map_loader package not working in UTM coordinates (#293) Signed-off-by: tanaka3 --- map_launch/launch/map.launch.py | 14 +++++++++++++- map_launch/launch/map.launch.xml | 4 ++++ 2 files changed, 17 insertions(+), 1 deletion(-) diff --git a/map_launch/launch/map.launch.py b/map_launch/launch/map.launch.py index a4ae541856..c4e6fad4f0 100644 --- a/map_launch/launch/map.launch.py +++ b/map_launch/launch/map.launch.py @@ -11,7 +11,9 @@ # 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 +from ament_index_python.packages import get_package_share_directory import launch from launch.actions import DeclareLaunchArgument from launch.actions import GroupAction @@ -23,9 +25,17 @@ from launch_ros.actions import Node from launch_ros.actions import PushRosNamespace from launch_ros.descriptions import ComposableNode +import yaml def generate_launch_description(): + + lanelet2_map_origin_path = os.path.join( + get_package_share_directory("map_loader"), "config/lanelet2_map_loader.param.yaml" + ) + + with open(lanelet2_map_origin_path, "r") as f: + lanelet2_map_origin_param = yaml.safe_load(f)["/**"]["ros__parameters"] map_hash_generator = Node( package="map_loader", executable="map_hash_generator", @@ -47,7 +57,9 @@ def generate_launch_description(): { "center_line_resolution": 5.0, "lanelet2_map_path": LaunchConfiguration("lanelet2_map_path"), - } + "lanelet2_map_projector_type": "MGRS", # Options: MGRS, UTM + }, + lanelet2_map_origin_param, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) diff --git a/map_launch/launch/map.launch.xml b/map_launch/launch/map.launch.xml index 5bedbc1d56..49746c39a9 100644 --- a/map_launch/launch/map.launch.xml +++ b/map_launch/launch/map.launch.xml @@ -1,4 +1,5 @@ + @@ -12,6 +13,9 @@ + + + From d7ed10b4553fa0b896a430a0f04d5bdd0053b663 Mon Sep 17 00:00:00 2001 From: Kazuki Matsumoto <59071591+kazuki527@users.noreply.github.com> Date: Mon, 25 Apr 2022 16:00:09 +0900 Subject: [PATCH 465/851] feat(planning_error_monitor): read params from yaml (#294) * feat(planning_error_monitor): read params from yaml * fix(planning_error_monitor): fix the parameter to paramter in universe. * fix: add units of some parameters in yaml --- .../planning_diagnostics/planning_error_monitor.param.yaml | 7 +++++++ .../planning_diagnostics/planning_error_monitor.launch.xml | 2 ++ 2 files changed, 9 insertions(+) create mode 100644 planning_launch/config/planning_diagnostics/planning_error_monitor.param.yaml diff --git a/planning_launch/config/planning_diagnostics/planning_error_monitor.param.yaml b/planning_launch/config/planning_diagnostics/planning_error_monitor.param.yaml new file mode 100644 index 0000000000..d52f24553b --- /dev/null +++ b/planning_launch/config/planning_diagnostics/planning_error_monitor.param.yaml @@ -0,0 +1,7 @@ +/**: + ros__parameters: + # trajectory check + error_interval: 100.0 # error interval distance threshold [m] + error_curvature: 2.0 # error curvature threshold [rad/m] + error_sharp_angle: 0.785398 # error sharp angle threshold [rad] + ignore_too_close_points: 0.01 # ignore too close distance threshold [m] diff --git a/planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml b/planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml index 0555cbf965..e3960f8ec0 100644 --- a/planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml +++ b/planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml @@ -3,6 +3,8 @@ + + From baa87252123bf750bc9e54c862926ac325bf91dd Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 26 Apr 2022 10:11:38 +0900 Subject: [PATCH 466/851] chore: sync files (#297) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/sync-files.yaml | 7 +++++++ setup.cfg | 2 +- 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/.github/workflows/sync-files.yaml b/.github/workflows/sync-files.yaml index 69ef19c684..b9dc5907a5 100644 --- a/.github/workflows/sync-files.yaml +++ b/.github/workflows/sync-files.yaml @@ -6,7 +6,14 @@ on: workflow_dispatch: jobs: + check-secret: + uses: autowarefoundation/autoware-github-actions/.github/workflows/check-secret.yaml@v1 + secrets: + secret: ${{ secrets.APP_ID }} + sync-files: + needs: check-secret + if: ${{ needs.check-secret.outputs.set == 'true' }} runs-on: ubuntu-latest steps: - name: Generate token diff --git a/setup.cfg b/setup.cfg index fd61ed536e..5214751c7b 100644 --- a/setup.cfg +++ b/setup.cfg @@ -1,7 +1,7 @@ [flake8] # Modified from https://github.com/ament/ament_lint/blob/ebd524bb9973d5ec1dc48a670ce54f958a5a0243/ament_flake8/ament_flake8/configuration/ament_flake8.ini extend-ignore = B902,C816,D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404,I202,CNL100,E203,E501,Q000 -import-order-style = google +import-order-style = pep8 max-line-length = 100 show-source = true statistics = true From 3cccfbe6c5649fa8aebf6c2a424c50dee8923fb3 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 26 Apr 2022 01:57:34 +0000 Subject: [PATCH 467/851] ci(pre-commit): autoupdate (#296) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * ci(pre-commit): autoupdate updates: - [github.com/tier4/pre-commit-hooks-ros: v0.6.0 → v0.7.0](https://github.com/tier4/pre-commit-hooks-ros/compare/v0.6.0...v0.7.0) * Update .pre-commit-config.yaml Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .pre-commit-config.yaml | 19 ++----------------- 1 file changed, 2 insertions(+), 17 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 6248132b9f..8c65d067ed 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -34,8 +34,9 @@ repos: - id: yamllint - repo: https://github.com/tier4/pre-commit-hooks-ros - rev: v0.6.0 + rev: v0.7.0 hooks: + - id: flake8-ros - id: prettier-package-xml - id: sort-package-xml @@ -61,20 +62,4 @@ repos: - id: black args: [--line-length=100] - - repo: https://github.com/PyCQA/flake8 - rev: 4.0.1 - hooks: - - id: flake8 - additional_dependencies: - [ - flake8-blind-except, - flake8-builtins, - flake8-class-newline, - flake8-comprehensions, - flake8-deprecated, - flake8-docstrings, - flake8-import-order, - flake8-quotes, - ] - exclude: .svg From 90763af3a35e7c8d27ee1ac2d29cff520149111b Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Tue, 26 Apr 2022 20:49:14 +0900 Subject: [PATCH 468/851] feat: change object_association_merger name (#299) * feat: change object_association_merger name Signed-off-by: tomoya.kimura * fix Signed-off-by: tomoya.kimura --- ...ra_lidar_fusion_based_detection.launch.xml | 25 +++++++++++-------- 1 file changed, 15 insertions(+), 10 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 b0bf3263dc..af20464cdf 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 @@ -147,15 +147,20 @@ - - - - - - - - - - + + + + + + + + + + + + + + + From 92e8f2e3590c26ee789874413184ec6d04297924 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Wed, 27 Apr 2022 19:18:21 +0900 Subject: [PATCH 469/851] fix(dummy_diag_publisher): delete duplicates (#300) --- system_launch/launch/dummy_diag_publisher/system.launch.xml | 4 ---- 1 file changed, 4 deletions(-) diff --git a/system_launch/launch/dummy_diag_publisher/system.launch.xml b/system_launch/launch/dummy_diag_publisher/system.launch.xml index 164dfe2e12..e56227a7a4 100644 --- a/system_launch/launch/dummy_diag_publisher/system.launch.xml +++ b/system_launch/launch/dummy_diag_publisher/system.launch.xml @@ -60,10 +60,6 @@ - - - - From e95e24375175a76c4dc91e3b9bb43fc55e3918d2 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 28 Apr 2022 00:58:40 +0900 Subject: [PATCH 470/851] feat(planning_launch): add bounds_search_widths (#295) Signed-off-by: Takayuki Murooka --- .../obstacle_avoidance_planner.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 40b64b7d87..bc3962ca5a 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -123,6 +123,8 @@ eps_rel: 1.0e-10 # eps rel when solving OSQP mpt: + bounds_search_widths: [0.45, 0.15, 0.05, 0.01] + clearance: # clearance(distance) between vehicle and roads/objects when generating trajectory hard_clearance_from_road: 0.0 # clearance from road boundary[m] soft_clearance_from_road: 0.1 # clearance from road boundary[m] From 0e25ac873ed5aeec7017cd4b9d5c57364116558f Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Thu, 28 Apr 2022 14:32:00 +0900 Subject: [PATCH 471/851] perf(trajectory_follower_nodes): change longitudinal control to use period parameter (#301) Signed-off-by: tomoya.kimura --- .../trajectory_follower/longitudinal_controller.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml index 3c9d79c8f7..d6b987f542 100644 --- a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml +++ b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml @@ -1,6 +1,6 @@ /**: ros__parameters: - control_rate: 30.0 + longitudinal_ctrl_period: 0.03 delay_compensation_time: 0.17 enable_smooth_stop: true From 8bddcdae72100382695245cff1c3953f46943710 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 3 May 2022 13:40:49 +0900 Subject: [PATCH 472/851] chore: sync files (#302) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/github-release.yaml | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 7bb9d70931..23508e63bc 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -51,9 +51,23 @@ jobs: id: generate-changelog uses: autowarefoundation/autoware-github-actions/generate-changelog@v1 + - name: Select verb + id: select-verb + run: | + has_previous_draft=$(gh release view --json isDraft -q ".isDraft" "${{ steps.set-tag-name.outputs.tag-name }}") + + verb=create + if [ "$has_previous_draft" = "true" ]; then + verb=edit + fi + + echo ::set-output name=verb::"$verb" + env: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} + - name: Release to GitHub run: | - gh release create "${{ steps.set-tag-name.outputs.tag-name }}" \ + gh release ${{ steps.select-verb.outputs.verb }} "${{ steps.set-tag-name.outputs.tag-name }}" \ --draft \ --target "${{ steps.set-target-name.outputs.target-name }}" \ --title "Release ${{ steps.set-tag-name.outputs.tag-name }}" \ From bef983f9becb6760547a192cb800de1d0e488383 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 10 May 2022 08:29:19 +0900 Subject: [PATCH 473/851] feat(planning_launch): separate surround_obstacle_checker from hierarchical motion planning flow (#304) --- .../motion_planning/motion_planning.launch.py | 34 ++++--------------- .../motion_planning.launch.xml | 13 +------ 2 files changed, 8 insertions(+), 39 deletions(-) diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index 58b6859194..2df9795b84 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -83,20 +83,23 @@ def generate_launch_description(): surround_obstacle_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] surround_obstacle_checker_component = ComposableNode( package="surround_obstacle_checker", - plugin="SurroundObstacleCheckerNode", + plugin="surround_obstacle_checker::SurroundObstacleCheckerNode", name="surround_obstacle_checker", namespace="", remappings=[ ("~/output/no_start_reason", "/planning/scenario_planning/status/no_start_reason"), ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), - ("~/output/trajectory", "surround_obstacle_checker/trajectory"), + ("~/output/max_velocity", "/planning/scenario_planning/max_velocity_candidates"), + ( + "~/output/velocity_limit_clear_command", + "/planning/scenario_planning/clear_velocity_limit", + ), ( "~/input/pointcloud", "/perception/obstacle_segmentation/pointcloud", ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), ], parameters=[ surround_obstacle_checker_param, @@ -104,22 +107,6 @@ def generate_launch_description(): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - # relay - relay_component = ComposableNode( - package="topic_tools", - plugin="topic_tools::RelayNode", - name="skip_surround_obstacle_check_relay", - namespace="", - parameters=[ - { - "input_topic": "obstacle_avoidance_planner/trajectory", - "output_topic": "surround_obstacle_checker/trajectory", - "type": "autoware_auto_planning_msgs/msg/Trajectory", - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - # obstacle stop planner obstacle_stop_planner_param_path = os.path.join( get_package_share_directory("planning_launch"), @@ -163,7 +150,7 @@ def generate_launch_description(): ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/trajectory", "surround_obstacle_checker/trajectory"), + ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), ], parameters=[ common_param, @@ -191,12 +178,6 @@ def generate_launch_description(): condition=IfCondition(LaunchConfiguration("use_surround_obstacle_check")), ) - relay_loader = LoadComposableNodes( - composable_node_descriptions=[relay_component], - target_container=container, - condition=UnlessCondition(LaunchConfiguration("use_surround_obstacle_check")), - ) - set_container_executable = SetLaunchConfiguration( "container_executable", "component_container", @@ -221,6 +202,5 @@ def generate_launch_description(): set_container_mt_executable, container, surround_obstacle_checker_loader, - relay_loader, ] ) 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 0ace2bbcc6..de101a8040 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 @@ -18,21 +18,10 @@ - - - - - - - - - - - @@ -42,7 +31,7 @@ - + From 3776ed79a057049a5806d07d37a4d7268d8fc73e Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Thu, 12 May 2022 10:21:07 +0900 Subject: [PATCH 474/851] chore: sync files (#303) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/github-release.yaml | 2 +- .markdown-link-check.json | 3 +++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 23508e63bc..93533b54e1 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -54,7 +54,7 @@ jobs: - name: Select verb id: select-verb run: | - has_previous_draft=$(gh release view --json isDraft -q ".isDraft" "${{ steps.set-tag-name.outputs.tag-name }}") + has_previous_draft=$(gh release view --json isDraft -q ".isDraft" "${{ steps.set-tag-name.outputs.tag-name }}") || true verb=create if [ "$has_previous_draft" = "true" ]; then diff --git a/.markdown-link-check.json b/.markdown-link-check.json index 331095d38d..dec3db1ad1 100644 --- a/.markdown-link-check.json +++ b/.markdown-link-check.json @@ -3,6 +3,9 @@ "ignorePatterns": [ { "pattern": "^http://localhost" + }, + { + "pattern": "^https://github.com/.*/discussions/new" } ], "retryOn429": true, From 671deb46d649a75ba6b087e34fb35797d426b8be Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 May 2022 14:51:40 +0900 Subject: [PATCH 475/851] feat: use tier4_map_launch instead of map_launch (#308) --- autoware_launch/launch/autoware.launch.xml | 2 +- .../launch/logging_simulator.launch.xml | 2 +- .../launch/planning_simulator.launch.xml | 2 +- map_launch/CMakeLists.txt | 22 -- map_launch/README.md | 28 -- map_launch/launch/map.launch.py | 154 ----------- map_launch/launch/map.launch.xml | 26 -- map_launch/map_launch.drawio.svg | 250 ------------------ map_launch/package.xml | 22 -- 9 files changed, 3 insertions(+), 505 deletions(-) delete mode 100644 map_launch/CMakeLists.txt delete mode 100644 map_launch/README.md delete mode 100644 map_launch/launch/map.launch.py delete mode 100644 map_launch/launch/map.launch.xml delete mode 100644 map_launch/map_launch.drawio.svg delete mode 100644 map_launch/package.xml diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index a2f9a9b489..26feca2216 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -44,7 +44,7 @@ - + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 49be3e16ab..9dd604812b 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -60,7 +60,7 @@ - + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index aa5e0e4179..e9cb8c5f1e 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -47,7 +47,7 @@ - + diff --git a/map_launch/CMakeLists.txt b/map_launch/CMakeLists.txt deleted file mode 100644 index d32f7c28c9..0000000000 --- a/map_launch/CMakeLists.txt +++ /dev/null @@ -1,22 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(map_launch) - -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() - -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/README.md b/map_launch/README.md deleted file mode 100644 index 5b36fb8e4b..0000000000 --- a/map_launch/README.md +++ /dev/null @@ -1,28 +0,0 @@ -# map_launch - -## Structure - -![map_launch](./map_launch.drawio.svg) - -## Package Dependencies - -Please see `` in `package.xml`. - -## Usage - -You can include as follows in `*.launch.xml` to use `map.launch.py`. - -```xml - - - - - - - - -``` - -## Notes - -For reducing processing load, we use the [Component](https://docs.ros.org/en/galactic/Concepts/About-Composition.html) feature in ROS2 (similar to Nodelet in ROS1 ) diff --git a/map_launch/launch/map.launch.py b/map_launch/launch/map.launch.py deleted file mode 100644 index c4e6fad4f0..0000000000 --- a/map_launch/launch/map.launch.py +++ /dev/null @@ -1,154 +0,0 @@ -# Copyright 2021 Tier IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -import os - -from ament_index_python.packages import get_package_share_directory -import launch -from launch.actions import DeclareLaunchArgument -from launch.actions import GroupAction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import Node -from launch_ros.actions import PushRosNamespace -from launch_ros.descriptions import ComposableNode -import yaml - - -def generate_launch_description(): - - lanelet2_map_origin_path = os.path.join( - get_package_share_directory("map_loader"), "config/lanelet2_map_loader.param.yaml" - ) - - with open(lanelet2_map_origin_path, "r") as f: - lanelet2_map_origin_param = yaml.safe_load(f)["/**"]["ros__parameters"] - map_hash_generator = Node( - package="map_loader", - executable="map_hash_generator", - name="map_hash_generator", - parameters=[ - { - "lanelet2_map_path": LaunchConfiguration("lanelet2_map_path"), - "pointcloud_map_path": LaunchConfiguration("pointcloud_map_path"), - } - ], - ) - - lanelet2_map_loader = ComposableNode( - package="map_loader", - plugin="Lanelet2MapLoaderNode", - name="lanelet2_map_loader", - remappings=[("output/lanelet2_map", "vector_map")], - parameters=[ - { - "center_line_resolution": 5.0, - "lanelet2_map_path": LaunchConfiguration("lanelet2_map_path"), - "lanelet2_map_projector_type": "MGRS", # Options: MGRS, UTM - }, - lanelet2_map_origin_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - lanelet2_map_visualization = ComposableNode( - package="map_loader", - plugin="Lanelet2MapVisualizationNode", - name="lanelet2_map_visualization", - remappings=[ - ("input/lanelet2_map", "vector_map"), - ("output/lanelet2_map_marker", "vector_map_marker"), - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - pointcloud_map_loader = ComposableNode( - package="map_loader", - plugin="PointCloudMapLoaderNode", - name="pointcloud_map_loader", - remappings=[("output/pointcloud_map", "pointcloud_map")], - parameters=[ - {"pcd_paths_or_directory": ["[", LaunchConfiguration("pointcloud_map_path"), "]"]} - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - map_tf_generator = ComposableNode( - package="map_tf_generator", - plugin="MapTFGeneratorNode", - name="map_tf_generator", - parameters=[ - { - "map_frame": "map", - "viewer_frame": "viewer", - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - container = ComposableNodeContainer( - name="map_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[ - lanelet2_map_loader, - lanelet2_map_visualization, - pointcloud_map_loader, - map_tf_generator, - ], - output="screen", - ) - - def add_launch_arg(name: str, default_value=None, description=None): - return DeclareLaunchArgument(name, default_value=default_value, description=description) - - return launch.LaunchDescription( - [ - add_launch_arg("map_path", "", "path to map directory"), - add_launch_arg( - "lanelet2_map_path", - [LaunchConfiguration("map_path"), "/lanelet2_map.osm"], - "path to lanelet2 map file", - ), - add_launch_arg( - "pointcloud_map_path", - [LaunchConfiguration("map_path"), "/pointcloud_map.pcd"], - "path to pointcloud map file", - ), - add_launch_arg( - "use_intra_process", "false", "use ROS2 component container communication" - ), - add_launch_arg("use_multithread", "false", "use multithread"), - SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ), - SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ), - GroupAction( - [ - PushRosNamespace("map"), - container, - map_hash_generator, - ] - ), - ] - ) diff --git a/map_launch/launch/map.launch.xml b/map_launch/launch/map.launch.xml deleted file mode 100644 index 49746c39a9..0000000000 --- a/map_launch/launch/map.launch.xml +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/map_launch/map_launch.drawio.svg b/map_launch/map_launch.drawio.svg deleted file mode 100644 index c037a46c14..0000000000 --- a/map_launch/map_launch.drawio.svg +++ /dev/null @@ -1,250 +0,0 @@ - - - - - - - -
    -
    -
    - map_container -
    -
    -
    - - package: rclcpp_components - -
    -
    -
    -
    -
    - - map_container... - -
    -
    - - - - -
    -
    -
    - map.launch.py -
    -
    -
    - - package: map_launch - -
    -
    -
    -
    -
    - - map.launch.py... - -
    -
    - - - - - - -
    -
    -
    - launch name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - launch name... - -
    -
    - - - - -
    -
    -
    - ex: -
    -
    -
    -
    - - ex: - -
    -
    - - - - -
    -
    -
    - node name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - node name... - -
    -
    - - - - -
    -
    -
    - other name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - other name... - -
    -
    - - - - -
    -
    -
    - lanelet2_map_loader -
    -
    -
    - - package: map_loader - -
    -
    -
    -
    -
    - - lanelet2_map_loader... - -
    -
    - - - - -
    -
    -
    - lanelet2_map_visualization -
    -
    -
    - - package: map_loader - -
    -
    -
    -
    -
    - - lanelet2_map_visualization... - -
    -
    - - - - -
    -
    -
    - pointcloud_map_loader -
    -
    -
    - - package: map_loader - -
    -
    -
    -
    -
    - - pointcloud_map_loader... - -
    -
    - - - - -
    -
    -
    - - map_tf_generator - -
    -
    -
    - - package: map_tf_generator - -
    -
    -
    -
    -
    - - map_tf_generator... - -
    -
    -
    - - - - - Viewer does not support full SVG 1.1 - - - -
    \ No newline at end of file diff --git a/map_launch/package.xml b/map_launch/package.xml deleted file mode 100644 index b8f7613344..0000000000 --- a/map_launch/package.xml +++ /dev/null @@ -1,22 +0,0 @@ - - - map_launch - 0.1.0 - The map_launch package - - mitsudome-r - - Apache License 2.0 - - ament_cmake_auto - - map_loader - map_tf_generator - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - From 7eff3c105d46bdf5d33a14ac9d1f570da2b69f15 Mon Sep 17 00:00:00 2001 From: Azumi Suzuki <38061530+s-azumi@users.noreply.github.com> Date: Thu, 12 May 2022 15:39:00 +0900 Subject: [PATCH 476/851] fix(perception_launch): enable to change the input pointcloud topic of the object segmentation and occupancy grid map modules in the perception launch (#306) --- .../ground_segmentation/ground_segmentation.launch.py | 3 ++- perception_launch/launch/perception.launch.xml | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index d44af6fac0..885315f871 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -460,7 +460,7 @@ def launch_setup(context, *args, **kwargs): components = [] components.extend( pipeline.create_single_frame_obstacle_segmentation_components( - input_topic="/sensing/lidar/concatenated/pointcloud", + input_topic=LaunchConfiguration("input/pointcloud"), output_topic=pipeline.single_frame_obstacle_seg_output, ) ) @@ -513,6 +513,7 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("use_intra_process", "True") add_launch_arg("use_pointcloud_container", "False") add_launch_arg("container_name", "perception_pipeline_container") + add_launch_arg("input/pointcloud", "sensing/lidar/concatenated/pointcloud") set_container_executable = SetLaunchConfiguration( "container_executable", diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 5b652bac5c..1b5b2d750a 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -40,6 +40,7 @@ +
    @@ -48,7 +49,7 @@ - + From 66101a65ae65cc3cbb33403abb781f55e33c3d53 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Fri, 13 May 2022 12:03:51 +0900 Subject: [PATCH 477/851] fix: exec_depend for map_launch (#310) * fix: exec_depend for map_launch * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- README.md | 1 - autoware_launch/package.xml | 2 +- integration_launch/package.xml | 2 +- 3 files changed, 2 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 94519ba3a9..b1ff82b201 100644 --- a/README.md +++ b/README.md @@ -20,7 +20,6 @@ ros2 launch autoware_launch planning_simulator.launch.xml map_path:=/path/to/map - [control_launch](./control_launch) - [integration_launch](./integration_launch) - [localization_launch](./localization_launch) -- [map_launch](./map_launch) - [perception_launch](./perception_launch) - [planning_launch](./planning_launch) - [sensing_launch](./sensing_launch) diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index ff6f4dba92..7fc7ef25bf 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -13,7 +13,6 @@ control_launch global_parameter_loader localization_launch - map_launch perception_launch planning_launch python3-bson @@ -22,6 +21,7 @@ sensing_launch simulator_launch system_launch + tier4_map_launch vehicle_launch web_controller diff --git a/integration_launch/package.xml b/integration_launch/package.xml index 07cf7e3a12..e27b57bd88 100644 --- a/integration_launch/package.xml +++ b/integration_launch/package.xml @@ -10,7 +10,6 @@ control_launch localization_launch - map_launch perception_launch planning_launch python3-bson @@ -18,6 +17,7 @@ rviz2 sensing_launch system_launch + tier4_map_launch vehicle_launch web_controller From 11da1f7d8ece2a296d34269067359af2e45a0e6a Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Mon, 16 May 2022 15:04:01 +0900 Subject: [PATCH 478/851] feat: use tier4_sensing_launch instead of sensing_launch (#309) * feat: use tier4_sensing_launch instead of sensing_launch * feat: change exec_depend * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- autoware_launch/launch/autoware.launch.xml | 2 +- .../launch/logging_simulator.launch.xml | 2 +- autoware_launch/package.xml | 2 +- sensing_launch/CMakeLists.txt | 14 -- sensing_launch/README.md | 48 ---- sensing_launch/launch/sensing.launch.xml | 24 -- sensing_launch/package.xml | 19 -- sensing_launch/sensing_launch.drawio.svg | 228 ------------------ 8 files changed, 3 insertions(+), 336 deletions(-) delete mode 100644 sensing_launch/CMakeLists.txt delete mode 100644 sensing_launch/README.md delete mode 100644 sensing_launch/launch/sensing.launch.xml delete mode 100644 sensing_launch/package.xml delete mode 100644 sensing_launch/sensing_launch.drawio.svg diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 26feca2216..02d6c33630 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -52,7 +52,7 @@ - + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 9dd604812b..7fc5751529 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -68,7 +68,7 @@ - + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 7fc7ef25bf..fa7f7aad14 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -18,10 +18,10 @@ python3-bson python3-tornado rviz2 - sensing_launch simulator_launch system_launch tier4_map_launch + tier4_sensing_launch vehicle_launch web_controller diff --git a/sensing_launch/CMakeLists.txt b/sensing_launch/CMakeLists.txt deleted file mode 100644 index 408ba2fe4a..0000000000 --- a/sensing_launch/CMakeLists.txt +++ /dev/null @@ -1,14 +0,0 @@ -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/README.md b/sensing_launch/README.md deleted file mode 100644 index 68d14582d0..0000000000 --- a/sensing_launch/README.md +++ /dev/null @@ -1,48 +0,0 @@ -# sensing_launch - -## Structure - -![sensing_launch](./sensing_launch.drawio.svg) - -## Package Dependencies - -Please see `` in `package.xml`. - -## Usage - -You can include as follows in `*.launch.xml` to use `sensing.launch.xml`. - -```xml - - - - - -``` - -## Launch Directory Structure - -This package finds sensor settings of specified sensor model in `launch`. - -```bash -launch/ -├── aip_x1 # Sensor model name -│   ├── camera.launch.xml # Camera -│   ├── gnss.launch.xml # GNSS -│   ├── imu.launch.xml # IMU -│   ├── lidar.launch.xml # LiDAR -│   └── pointcloud_preprocessor.launch.py # for preprocessing pointcloud -... -``` - -## Notes - -This package finds settings with variables. - -ex.) - - - -```xml - -``` diff --git a/sensing_launch/launch/sensing.launch.xml b/sensing_launch/launch/sensing.launch.xml deleted file mode 100644 index cc0393234b..0000000000 --- a/sensing_launch/launch/sensing.launch.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/package.xml b/sensing_launch/package.xml deleted file mode 100644 index b5012e35ed..0000000000 --- a/sensing_launch/package.xml +++ /dev/null @@ -1,19 +0,0 @@ - - - - sensing_launch - 0.1.0 - The sensing_launch package - - Yukihiro Saito - Apache License 2.0 - - ament_cmake_auto - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/sensing_launch/sensing_launch.drawio.svg b/sensing_launch/sensing_launch.drawio.svg deleted file mode 100644 index 4db34b058b..0000000000 --- a/sensing_launch/sensing_launch.drawio.svg +++ /dev/null @@ -1,228 +0,0 @@ - - - - - - - -
    -
    -
    - sensing.launch.xml -
    -
    -
    - - package: sensing_launch - -
    -
    -
    -
    -
    - - sensing.launch.xml... - -
    -
    - - - - -
    -
    -
    - lidar.launch.xml -
    -
    -
    - package: sensing_launch -
    -
    -
    -
    -
    - - lidar.launch.xml... - -
    -
    - - - - - - - - -
    -
    -
    - camera.launch.xml -
    -
    -
    - - package: sensing_launch - -
    -
    -
    -
    -
    - - camera.launch.xml... - -
    -
    - - - - -
    -
    -
    - launch name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - launch name... - -
    -
    - - - - -
    -
    -
    - ex: -
    -
    -
    -
    - - ex: - -
    -
    - - - - -
    -
    -
    - node name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - node name... - -
    -
    - - - - -
    -
    -
    - other name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - other name... - -
    -
    - - - - -
    -
    -
    - imu.launch.xml -
    -
    -
    - - package: sensing_launch - -
    -
    -
    -
    -
    - - imu.launch.xml... - -
    -
    - - - - -
    -
    -
    - imu.launch.xml -
    -
    -
    - - package: sensing_launch - -
    -
    -
    -
    -
    - - imu.launch.xml... - -
    -
    - - - - -
    - - - - - Viewer does not support full SVG 1.1 - - - -
    \ No newline at end of file From 00c3607c65ab6526044c99555acc7cd26665060c Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 17 May 2022 21:02:42 +0900 Subject: [PATCH 479/851] fix: rosdep install error due to sensing_launch (#313) Signed-off-by: kosuke55 --- integration_launch/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/integration_launch/package.xml b/integration_launch/package.xml index e27b57bd88..54d42a8492 100644 --- a/integration_launch/package.xml +++ b/integration_launch/package.xml @@ -15,9 +15,9 @@ python3-bson python3-tornado rviz2 - sensing_launch system_launch tier4_map_launch + tier4_sensing_launch vehicle_launch web_controller From d626c3286e949d5bea1940d81aabb9db2bbe50e7 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 20 May 2022 12:41:47 +0900 Subject: [PATCH 480/851] feat(planning_launch): update obstacle avoidance params (#315) * add new obstacle avoidance changes * prepare rear_drive and uniform_circle constraints Signed-off-by: Takayuki Murooka * use rear_drive by default Signed-off-by: Takayuki Murooka * remove unnecessary code Signed-off-by: Takayuki Murooka --- .../obstacle_avoidance_planner.param.yaml | 44 +++++-------------- 1 file changed, 10 insertions(+), 34 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index bc3962ca5a..667d2644f1 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -83,28 +83,6 @@ # advanced parameters to improve performance as much as possible advanced: - option: - # check if planned trajectory is outside drivable area - drivability_check: - # true: vehicle shape is considered as a set of circles - # false: vehicle shape is considered as footprint (= rectangle) - use_vehicle_circles: false - - # parameters only when use_vehicle_circles is true - vehicle_circles: - use_manual_vehicle_circles: false - num_for_constraints: 4 - - # parameters only when use_manual_vehicle_circles is true - longitudinal_offsets: [-0.15, 0.88, 1.9, 2.95] - radius: 0.95 - - # parameters only when use_manual_vehicle_circles is false - radius_ratio: 0.9 - # If this parameter is commented out, the parameter is calculated automatically - # based on the vehicle length and width - # num_for_radius: 4 - eb: common: num_joint_buffer_points: 3 # number of joint buffer points @@ -161,15 +139,13 @@ # two_step_soft_constraint: false vehicle_circles: - use_manual_vehicle_circles: false - num_for_constraints: 3 - - # parameters only when use_manual_vehicle_circles is true - longitudinal_offsets: [-0.15, 0.88, 1.9, 2.95] - radius: 0.95 - - # parameters only when use_manual_vehicle_circles is false - radius_ratio: 0.8 - # If this parameter is commented out, the parameter is calculated automatically - # based on the vehicle length and width - # num_for_radius: 4 + method: "rear_drive" + + uniform_circle: + num: 3 + radius_ratio: 0.8 + + rear_drive: + num_for_calculation: 3 + front_radius_ratio: 1.0 + rear_radius_ratio: 1.0 From bd4e4a4899a87dd5d0d5fd6710d1baa8624885dc Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Fri, 20 May 2022 06:28:56 +0000 Subject: [PATCH 481/851] chore: sync files (#311) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/github-release.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 93533b54e1..19e1e9c12e 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -9,6 +9,7 @@ on: workflow_dispatch: inputs: beta-branch-or-tag-name: + description: The name of the beta branch or tag to release type: string required: true From 66b473207ef81d4c98e394530f0cecae9f283bb6 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Fri, 20 May 2022 15:36:59 +0900 Subject: [PATCH 482/851] feat: disable namespace `lane_start_bound` (#314) * feat: disable lane_bound * fix: lane_start_bound * feat: add center_line_arrows to disable --- autoware_launch/rviz/autoware.rviz | 2 ++ 1 file changed, 2 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 28bed4d2e8..690e038e7a 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -373,7 +373,9 @@ Visualization Manager: Name: Lanelet2VectorMap Namespaces: center_lane_line: false + center_line_arrows: false crosswalk_lanelets: true + lane_start_bound: false lanelet direction: true lanelet_id: false left_lane_bound: true From 7fbe789651ec8215ba93b48229742b6c551fe9b8 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Fri, 20 May 2022 17:02:08 +0900 Subject: [PATCH 483/851] ci: add sync-awf.yaml (#318) * ci: add sync-awf.yaml Signed-off-by: Kenji Miyake * rename Signed-off-by: Kenji Miyake --- .github/workflows/sync-awf-latest.yaml | 31 ++++++++++++++++++++++++++ 1 file changed, 31 insertions(+) create mode 100644 .github/workflows/sync-awf-latest.yaml diff --git a/.github/workflows/sync-awf-latest.yaml b/.github/workflows/sync-awf-latest.yaml new file mode 100644 index 0000000000..6f905ef9e8 --- /dev/null +++ b/.github/workflows/sync-awf-latest.yaml @@ -0,0 +1,31 @@ +name: sync-awf-latest + +on: + schedule: + - cron: 0 0 * * * + workflow_dispatch: + +jobs: + sync-awf-latest: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + base-branch: tier4/universe + sync-pr-branch: sync-awf-latest + sync-target-repository: https://github.com/tier4/autoware_launch.git + sync-target-branch: awf-latest + pr-title: "chore: sync awf-latest" + pr-labels: | + bot + sync-awf-latest + auto-merge-method: merge From 3a79447b43bc329901e841dd8cafae347560287e Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 20 May 2022 20:19:59 +0900 Subject: [PATCH 484/851] refactor(vehicle_cmd_gate): add namespace (#316) Signed-off-by: Takamasa Horibe --- control_launch/launch/control.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 1d5cf26548..a4671689d1 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -159,7 +159,7 @@ def launch_setup(context, *args, **kwargs): # vehicle cmd gate vehicle_cmd_gate_component = ComposableNode( package="vehicle_cmd_gate", - plugin="VehicleCmdGate", + plugin="vehicle_cmd_gate::VehicleCmdGate", name="vehicle_cmd_gate", remappings=[ ("input/emergency_state", "/system/emergency/emergency_state"), From 5351cb86428cdafd9fcc0e90c40a2240dfa0547a Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Sat, 21 May 2022 00:29:16 +0900 Subject: [PATCH 485/851] style: fix flake8 C417 (#321) Signed-off-by: Kenji Miyake --- .../ground_segmentation/ground_segmentation.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 885315f871..b8781ebac1 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -265,7 +265,7 @@ def create_single_frame_obstacle_segmentation_components(self, input_topic, outp components.append( self.get_additional_lidars_concatenated_component( input_topics=[common_pipeline_output] - + list(map(lambda x: f"{x}/pointcloud", additional_lidars)), + + [f"{x}/pointcloud" for x in additional_lidars], output_topic=relay_topic if use_ransac else output_topic, ) ) From 996e9a7972e84416f3b03dd03d13c69929c491c6 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Mon, 23 May 2022 16:06:31 +0900 Subject: [PATCH 486/851] chore: sync awf-latest (#322) style: fix flake8 C417 (#321) Signed-off-by: Kenji Miyake Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .../ground_segmentation/ground_segmentation.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 885315f871..b8781ebac1 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -265,7 +265,7 @@ def create_single_frame_obstacle_segmentation_components(self, input_topic, outp components.append( self.get_additional_lidars_concatenated_component( input_topics=[common_pipeline_output] - + list(map(lambda x: f"{x}/pointcloud", additional_lidars)), + + [f"{x}/pointcloud" for x in additional_lidars], output_topic=relay_topic if use_ransac else output_topic, ) ) From 42c90a7d0c45434bf5ba6e1ae56a96af338a6c96 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Mon, 23 May 2022 19:45:19 +0900 Subject: [PATCH 487/851] chore(behavior_velocity): update latest params (#320) * chore(behavior_velocity): update latest params Signed-off-by: tanaka3 * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../occlusion_spot.param.yaml | 11 ++++++----- .../behavior_velocity_planner/stop_line.param.yaml | 2 ++ 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml index a2f16ee825..be846f70c4 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml @@ -4,6 +4,7 @@ detection_method: "occupancy_grid" # [-] candidate is "occupancy_grid" or "predicted_object" pass_judge: "smooth_velocity" # [-] candidate is "smooth_velocity" or "current_velocity" filter_occupancy_grid: true # [-] whether to filter occupancy grid by morphologyEx or not + use_moving_object_ray_cast: true # [-] whether to reflect moving object ray shadow grid map use_object_info: true # [-] whether to reflect object info to occupancy grid map or not use_partition_lanelet: true # [-] whether to use partition lanelet map data pedestrian_vel: 1.5 # [m/s] assume pedestrian is dashing from occlusion at this velocity @@ -18,8 +19,8 @@ lateral_distance: 1.5 # [m] maximum lateral distance to consider hidden collision motion: safety_ratio: 0.8 # [-] jerk/acceleration ratio for safety - max_slow_down_jerk: -0.5 # [m/s^3] minimum jerk deceleration for safe brake. - max_slow_down_accel: -1.8 # [m/s^2] minimum accel deceleration for safe brake. + max_slow_down_jerk: -0.3 # [m/s^3] minimum jerk deceleration for safe brake. + max_slow_down_accel: -1.5 # [m/s^2] minimum accel deceleration for safe brake. non_effective_jerk: -0.3 # [m/s^3] weak jerk for velocity planning. non_effective_acceleration: -1.0 # [m/s^2] weak deceleration for velocity planning. min_allowed_velocity: 1.0 # [m/s] minimum velocity allowed @@ -28,7 +29,7 @@ min_occlusion_spot_size: 1.0 # [m] occupancy grid must contain an UNKNOWN area of at least size NxN to be considered a hidden obstacle. slice_length: 10.0 # [m] size of slices in both length and distance relative to the ego path. min_longitudinal_offset: 1.0 # [m] detection area safety buffer from front bumper. - max_lateral_distance: 6.0 # [m] buffer around the ego path used to build the detection area. + max_lateral_distance: 5.0 # [m] buffer around the ego path used to build the detection area. grid: - free_space_max: 40 # [-] maximum value of a free space cell in the occupancy grid - occupied_min: 60 # [-] minimum value of an occupied cell in the occupancy grid + free_space_max: 43 # [-] maximum value of a free space cell in the occupancy grid + occupied_min: 57 # [-] minimum value of an occupied cell in the occupancy grid diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml index a2b5ac5d5f..6d723c510c 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml @@ -4,3 +4,5 @@ stop_margin: 0.0 stop_check_dist: 2.0 stop_duration_sec: 1.0 + debug: + show_stopline_collision_check: false # [-] whether to show stopline collision From b37456b7413bcde2541c56c7fcf815e6759a9ab0 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 24 May 2022 02:36:04 +0900 Subject: [PATCH 488/851] ci(pre-commit): autoupdate (#324) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit updates: - [github.com/tier4/pre-commit-hooks-ros: v0.7.0 → v0.7.1](https://github.com/tier4/pre-commit-hooks-ros/compare/v0.7.0...v0.7.1) - [github.com/scop/pre-commit-shfmt: v3.4.3-1 → v3.5.0-1](https://github.com/scop/pre-commit-shfmt/compare/v3.4.3-1...v3.5.0-1) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .pre-commit-config.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 8c65d067ed..ede7eb7ef7 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -34,7 +34,7 @@ repos: - id: yamllint - repo: https://github.com/tier4/pre-commit-hooks-ros - rev: v0.7.0 + rev: v0.7.1 hooks: - id: flake8-ros - id: prettier-package-xml @@ -46,7 +46,7 @@ repos: - id: shellcheck - repo: https://github.com/scop/pre-commit-shfmt - rev: v3.4.3-1 + rev: v3.5.0-1 hooks: - id: shfmt args: [-w, -s, -i=4] From 3ece3dc0b17270295d10ee5088cbedf25656ebd7 Mon Sep 17 00:00:00 2001 From: Kah Hooi Tan <41041286+tkhmy@users.noreply.github.com> Date: Tue, 24 May 2022 10:30:03 +0900 Subject: [PATCH 489/851] feat(autoware_api_launch): add rtc controller (#305) * add rtc controller Signed-off-by: tkhmy * change line Signed-off-by: tkhmy * change back to alphabetical order Signed-off-by: tkhmy --- .../launch/include/external_api_adaptor.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_api_launch/launch/include/external_api_adaptor.launch.py b/autoware_api_launch/launch/include/external_api_adaptor.launch.py index 4f1295588a..fb840f4edd 100644 --- a/autoware_api_launch/launch/include/external_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/external_api_adaptor.launch.py @@ -40,6 +40,7 @@ def generate_launch_description(): _create_api_node("operator", "Operator"), _create_api_node("metadata_packages", "MetadataPackages"), _create_api_node("route", "Route"), + _create_api_node("rtc_controller", "RTCController"), _create_api_node("service", "Service"), _create_api_node("start", "Start"), _create_api_node("vehicle_status", "VehicleStatus"), From be8d24c29d5f153c795f8a670362d0aa8baa615d Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Wed, 25 May 2022 10:32:06 +0900 Subject: [PATCH 490/851] chore: sync files (#327) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 2 +- .github/workflows/build-and-test.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index b77573e096..72b922a521 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -6,7 +6,7 @@ on: jobs: build-and-test-differential: runs-on: ubuntu-latest - container: ghcr.io/autowarefoundation/autoware-universe:latest + container: ros:galactic steps: - name: Cancel previous runs uses: styfle/cancel-workflow-action@0.9.1 diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index f0760d99ae..2d7ff34b79 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -10,7 +10,7 @@ jobs: build-and-test: if: ${{ github.event_name != 'push' || github.ref_name == github.event.repository.default_branch }} runs-on: ubuntu-latest - container: ghcr.io/autowarefoundation/autoware-universe:latest + container: ros:galactic steps: - name: Check out repository uses: actions/checkout@v3 From d66e786b97c67c732a29a909bcef658d1b32ee60 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 25 May 2022 07:21:17 -0400 Subject: [PATCH 491/851] refactor: virtual wall rviz config (#326) Signed-off-by: Takamasa Horibe --- autoware_launch/rviz/autoware.rviz | 944 ++++++++++++++--------------- 1 file changed, 469 insertions(+), 475 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 690e038e7a..c9bdce7059 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -42,8 +42,7 @@ Visualization Manager: Show Arrows: true Show Axes: true Show Names: true - Tree: - {} + Tree: {} Update Interval: 0 Value: false - Alpha: 0.5 @@ -650,8 +649,7 @@ Visualization Manager: - Class: rviz_default_plugins/MarkerArray Enabled: true Name: MonteCarloInitialPose - Namespaces: - {} + Namespaces: {} Topic: Depth: 5 Durability Policy: Volatile @@ -724,207 +722,174 @@ Visualization Manager: Name: Segmentation - Class: rviz_common/Group Displays: - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/DetectedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true - Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: DetectedObjects - Namespaces: - {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/detection/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 - Value: true - Enabled: false - Name: Detection - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/TrackedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true - Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: TrackedObjects - Namespaces: - {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/tracking/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 - Value: true - Enabled: false - Name: Tracking - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/PredictedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true - Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: PredictedObjects - Namespaces: - {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 - Value: true + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true Enabled: true - Name: Prediction - Enabled: true - Name: ObjectRecognition + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: DetectedObjects + Namespaces: {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/object_recognition/detection/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 + Value: true + Enabled: false + Name: Detection - Class: rviz_common/Group Displays: - - Class: rviz_default_plugins/Image + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/TrackedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true Enabled: true - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: RecognitionResultOnImage - Normalize Range: true + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: TrackedObjects + Namespaces: {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/traffic_light_recognition/debug/rois + Value: /perception/object_recognition/tracking/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 Value: true - - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Tracking + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/PredictedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: false + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: false + Display UUID: true + Display Velocity: true Enabled: true - Name: MapBasedDetectionResult - Namespaces: - {} + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: PredictedObjects + Namespaces: {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers + Value: /perception/object_recognition/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 Value: true Enabled: true - Name: TrafficLight + Name: Prediction - Class: rviz_common/Group Displays: - - Alpha: 0.5 - Class: rviz_default_plugins/Map - Color Scheme: map - Draw Behind: false + - Class: rviz_default_plugins/Image Enabled: true - Name: Map + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: RecognitionResultOnImage + Normalize Range: true Topic: Depth: 5 Durability Policy: Volatile - Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/occupancy_grid_map/map - Update Topic: + Value: /perception/traffic_light_recognition/debug/rois + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: MapBasedDetectionResult + Namespaces: {} + Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/occupancy_grid_map/map_updates - Use Timestamp: false + Value: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers Value: true - Enabled: false - Name: OccupancyGrid + Enabled: true + Name: TrafficLight Enabled: true Name: Perception - Class: rviz_common/Group @@ -1019,201 +984,6 @@ Visualization Manager: Constant Color: false Scale: 0.30000001192092896 Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Arrow - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Crosswalk - Namespaces: - collision line: false - collision point: false - factor_text: true - slow factor_text: true - slow point: false - slow polygon line: false - slow virtual_wall: true - stop point: false - stop polygon line: false - stop_virtual_wall: true - walkway stop judge range: false - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Intersection - Namespaces: - candidate_collision_ego_lane_polygon: false - candidate_collision_object_polygons: false - conflicting_targets: false - detection_area: false - ego_lane: false - factor_text: true - judge_point_pose_line: false - path_raw: false - spline: false - stop_point_pose_line: false - stop_virtual_wall: true - stuck_vehicle_detect_area: false - stuck_targets: false - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: MergeFromPrivate - Namespaces: - factor_text: true - stop_point_pose_line: false - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/merge_from_private - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Blind Spot - Namespaces: - conflict_area_for_blind_spot: false - conflicting_targets: false - detection_area: false - detection_area_for_blind_spot: false - factor_text: true - judge_point_pose_line: false - path_raw: false - stop_virtual_wall: true - spline: false - stop_point_pose_line: false - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/blind_spot - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: TrafficLight - Namespaces: - dead line factor_text: false - dead line virtual_wall: false - factor_text: true - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/traffic_light - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualTrafficLight - Namespaces: - end_lines: false - instrument_center: false - instrument_id: false - start_line: false - stop_factor_text: true - stop_line: false - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/virtual_traffic_light - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: StopLine - Namespaces: - factor_text: true - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/stop_line - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: DetectionArea - Namespaces: - detection_area_correspondence: false - detection_area_id: false - detection_area_polygon: false - factor_text: true - obstacles: false - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: OcclusionSpot - Namespaces: - arrow: false - occlusion spot slow down: true - collision: false - info_obstacle: false - obstacle: false - detection_area: false - slow factor_text: true - path_raw: false - path_interpolated: false - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/occlusion_spot - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: NoStoppingArea - Namespaces: - no_stopping_area_correspondence: false - no_stopping_area_id: false - no_stopping_area_polygon: false - stuck_vehicle_detect_area: false - stop_line_detect_area: false - stuck_points: false - stop_factor_text: true - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_stopping_area - Value: true - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true @@ -1237,18 +1007,255 @@ Visualization Manager: Constant Color: false Scale: 0.30000001192092896 Value: false - - Class: rviz_default_plugins/MarkerArray + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (BlindSpot) + 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/virtual_wall/blind_spot + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (Crosswalk) + 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/virtual_wall/crosswalk + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (DetectionArea) + 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/virtual_wall/detection_area + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (Intersection) + 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/virtual_wall/intersection + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (MergeFromPrivateArea) + 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/virtual_wall/merge_from_private + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (NoStoppingArea) + 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/virtual_wall/no_stopping_area + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (OcclusionSpot) + 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/virtual_wall/occlusion_spot + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (StopLine) + Namespaces: + stop_factor_text: true + stop_virtual_wall: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/stop_line + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (TrafficLight) + 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/virtual_wall/traffic_light + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (VirtualTrafficLight) + 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/virtual_wall/virtual_traffic_light + Value: true + Enabled: true + Name: VirtualWall + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Arrow + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Crosswalk + 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/crosswalk + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Intersection + 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/intersection + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Blind Spot + 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/blind_spot + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: TrafficLight + 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/traffic_light + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: VirtualTrafficLight + 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/virtual_traffic_light + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: StopLine + 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/stop_line + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: DetectionArea + 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/detection_area + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: OcclusionSpot + 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/occlusion_spot + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: NoStoppingArea + 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/no_stopping_area + Value: false Enabled: false - Name: DrivableAreaBoundary - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_boundary - Value: true + Name: DebugMarker Enabled: true Name: BehaviorPlanning - Class: rviz_common/Group @@ -1276,81 +1283,86 @@ Visualization Manager: Constant Color: false Scale: 0.30000001192092896 Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: ObstacleStop - Namespaces: - collision_polygons: false - detection_polygons: false - slow_down_polygons: false - slow_down_detection_polygons: false - stop_obstacle_point: false - stop_obstacle_text: false - slow_down_obstacle_point: false - slow_down_obstacle_text: false - slow_down_start_virtual_wall: false - slow_down_start_factor_text: false - slow_down_end_virtual_wall: false - slow_down_end_factor_text: false - slow_down_end: false - stop_virtual_wall: true - stop_factor_text: true - slow_down_virtual_wall: true - slow_down_factor_text: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker - Value: true - - Class: rviz_default_plugins/MarkerArray + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (ObstacleStop) + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/virtual_wall + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (SurroundObstacle) + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/virtual_wall + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (ObstacleAvoidance) + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/wall_marker + Value: true Enabled: true - Name: SurroundObstacleCheck - Namespaces: - factor_text: true - virtual_wall: true - obstacle_point: true - no_start_obstacle_text: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: ObstacleAvoidance - Namespaces: - base_bounds_0: false - base_bounds_1: false - base_bounds_2: false - current_vehicle_circles: false - lateral_errors: false - mpt_footprints: false - vehicle_circle_lines: false - vehicle_circles: false - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: ObstacleAvoidanceWall - Namespaces: - virtual_wall: true - virtual_wall_text: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/wall_marker - Value: true + Name: VirtualWall + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: ObstacleStop + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: SurroundObstacleCheck + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: ObstacleAvoidance + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker + Value: true + Enabled: false + Name: DebugMarker Enabled: true Name: MotionPlanning Enabled: true @@ -1419,22 +1431,6 @@ Visualization Manager: Value: true Enabled: true Name: Parking - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: TrajectoryErrorMarker - Namespaces: - trajectory_relative_angle: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/planning_diagnostics/planning_error_monitor/debug/marker - Value: true - Enabled: true - Name: PlanningDiagnostics Enabled: true Name: ScenarioPlanning Enabled: true @@ -1467,8 +1463,7 @@ Visualization Manager: - Class: rviz_default_plugins/MarkerArray Enabled: false Name: Debug/MPC - Namespaces: - {} + Namespaces: {} Topic: Depth: 5 Durability Policy: Volatile @@ -1479,14 +1474,13 @@ Visualization Manager: - Class: rviz_default_plugins/MarkerArray Enabled: false Name: Debug/PurePursuit - Namespaces: - {} + Namespaces: {} Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /control/trajectory_follower/pure_pursuit_node_exe/debug/markers + Value: /control/trajectory_follower/pure_pursuit/debug/markers Value: false Enabled: true Name: Control From 6ecd000d1b435648cc34404c4174b150de3c6a7d Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Wed, 25 May 2022 22:00:11 +0900 Subject: [PATCH 492/851] chore: sync awf-latest (#325) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * chore: sync files (#311) Signed-off-by: GitHub Co-authored-by: kenji-miyake * feat: disable namespace `lane_start_bound` (#314) * feat: disable lane_bound * fix: lane_start_bound * feat: add center_line_arrows to disable * ci: add sync-awf.yaml (#318) * ci: add sync-awf.yaml Signed-off-by: Kenji Miyake * rename Signed-off-by: Kenji Miyake * refactor(vehicle_cmd_gate): add namespace (#316) Signed-off-by: Takamasa Horibe * style: fix flake8 C417 (#321) Signed-off-by: Kenji Miyake * chore(behavior_velocity): update latest params (#320) * chore(behavior_velocity): update latest params Signed-off-by: tanaka3 * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * ci(pre-commit): autoupdate (#324) updates: - [github.com/tier4/pre-commit-hooks-ros: v0.7.0 → v0.7.1](https://github.com/tier4/pre-commit-hooks-ros/compare/v0.7.0...v0.7.1) - [github.com/scop/pre-commit-shfmt: v3.4.3-1 → v3.5.0-1](https://github.com/scop/pre-commit-shfmt/compare/v3.4.3-1...v3.5.0-1) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * feat(autoware_api_launch): add rtc controller (#305) * add rtc controller Signed-off-by: tkhmy * change line Signed-off-by: tkhmy * change back to alphabetical order Signed-off-by: tkhmy Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Co-authored-by: kenji-miyake Co-authored-by: Hiroki OTA Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Takamasa Horibe Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kah Hooi Tan <41041286+tkhmy@users.noreply.github.com> --- .github/workflows/github-release.yaml | 1 + .github/workflows/sync-awf-latest.yaml | 31 +++++++++++++++++++ .pre-commit-config.yaml | 4 +-- .../include/external_api_adaptor.launch.py | 1 + autoware_launch/rviz/autoware.rviz | 2 ++ control_launch/launch/control.launch.py | 2 +- .../occlusion_spot.param.yaml | 11 ++++--- .../stop_line.param.yaml | 2 ++ 8 files changed, 46 insertions(+), 8 deletions(-) create mode 100644 .github/workflows/sync-awf-latest.yaml diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 93533b54e1..19e1e9c12e 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -9,6 +9,7 @@ on: workflow_dispatch: inputs: beta-branch-or-tag-name: + description: The name of the beta branch or tag to release type: string required: true diff --git a/.github/workflows/sync-awf-latest.yaml b/.github/workflows/sync-awf-latest.yaml new file mode 100644 index 0000000000..6f905ef9e8 --- /dev/null +++ b/.github/workflows/sync-awf-latest.yaml @@ -0,0 +1,31 @@ +name: sync-awf-latest + +on: + schedule: + - cron: 0 0 * * * + workflow_dispatch: + +jobs: + sync-awf-latest: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + base-branch: tier4/universe + sync-pr-branch: sync-awf-latest + sync-target-repository: https://github.com/tier4/autoware_launch.git + sync-target-branch: awf-latest + pr-title: "chore: sync awf-latest" + pr-labels: | + bot + sync-awf-latest + auto-merge-method: merge diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 8c65d067ed..ede7eb7ef7 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -34,7 +34,7 @@ repos: - id: yamllint - repo: https://github.com/tier4/pre-commit-hooks-ros - rev: v0.7.0 + rev: v0.7.1 hooks: - id: flake8-ros - id: prettier-package-xml @@ -46,7 +46,7 @@ repos: - id: shellcheck - repo: https://github.com/scop/pre-commit-shfmt - rev: v3.4.3-1 + rev: v3.5.0-1 hooks: - id: shfmt args: [-w, -s, -i=4] diff --git a/autoware_api_launch/launch/include/external_api_adaptor.launch.py b/autoware_api_launch/launch/include/external_api_adaptor.launch.py index 4f1295588a..fb840f4edd 100644 --- a/autoware_api_launch/launch/include/external_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/external_api_adaptor.launch.py @@ -40,6 +40,7 @@ def generate_launch_description(): _create_api_node("operator", "Operator"), _create_api_node("metadata_packages", "MetadataPackages"), _create_api_node("route", "Route"), + _create_api_node("rtc_controller", "RTCController"), _create_api_node("service", "Service"), _create_api_node("start", "Start"), _create_api_node("vehicle_status", "VehicleStatus"), diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 28bed4d2e8..690e038e7a 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -373,7 +373,9 @@ Visualization Manager: Name: Lanelet2VectorMap Namespaces: center_lane_line: false + center_line_arrows: false crosswalk_lanelets: true + lane_start_bound: false lanelet direction: true lanelet_id: false left_lane_bound: true diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 1d5cf26548..a4671689d1 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -159,7 +159,7 @@ def launch_setup(context, *args, **kwargs): # vehicle cmd gate vehicle_cmd_gate_component = ComposableNode( package="vehicle_cmd_gate", - plugin="VehicleCmdGate", + plugin="vehicle_cmd_gate::VehicleCmdGate", name="vehicle_cmd_gate", remappings=[ ("input/emergency_state", "/system/emergency/emergency_state"), diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml index a2f16ee825..be846f70c4 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml @@ -4,6 +4,7 @@ detection_method: "occupancy_grid" # [-] candidate is "occupancy_grid" or "predicted_object" pass_judge: "smooth_velocity" # [-] candidate is "smooth_velocity" or "current_velocity" filter_occupancy_grid: true # [-] whether to filter occupancy grid by morphologyEx or not + use_moving_object_ray_cast: true # [-] whether to reflect moving object ray shadow grid map use_object_info: true # [-] whether to reflect object info to occupancy grid map or not use_partition_lanelet: true # [-] whether to use partition lanelet map data pedestrian_vel: 1.5 # [m/s] assume pedestrian is dashing from occlusion at this velocity @@ -18,8 +19,8 @@ lateral_distance: 1.5 # [m] maximum lateral distance to consider hidden collision motion: safety_ratio: 0.8 # [-] jerk/acceleration ratio for safety - max_slow_down_jerk: -0.5 # [m/s^3] minimum jerk deceleration for safe brake. - max_slow_down_accel: -1.8 # [m/s^2] minimum accel deceleration for safe brake. + max_slow_down_jerk: -0.3 # [m/s^3] minimum jerk deceleration for safe brake. + max_slow_down_accel: -1.5 # [m/s^2] minimum accel deceleration for safe brake. non_effective_jerk: -0.3 # [m/s^3] weak jerk for velocity planning. non_effective_acceleration: -1.0 # [m/s^2] weak deceleration for velocity planning. min_allowed_velocity: 1.0 # [m/s] minimum velocity allowed @@ -28,7 +29,7 @@ min_occlusion_spot_size: 1.0 # [m] occupancy grid must contain an UNKNOWN area of at least size NxN to be considered a hidden obstacle. slice_length: 10.0 # [m] size of slices in both length and distance relative to the ego path. min_longitudinal_offset: 1.0 # [m] detection area safety buffer from front bumper. - max_lateral_distance: 6.0 # [m] buffer around the ego path used to build the detection area. + max_lateral_distance: 5.0 # [m] buffer around the ego path used to build the detection area. grid: - free_space_max: 40 # [-] maximum value of a free space cell in the occupancy grid - occupied_min: 60 # [-] minimum value of an occupied cell in the occupancy grid + free_space_max: 43 # [-] maximum value of a free space cell in the occupancy grid + occupied_min: 57 # [-] minimum value of an occupied cell in the occupancy grid diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml index a2b5ac5d5f..6d723c510c 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml @@ -4,3 +4,5 @@ stop_margin: 0.0 stop_check_dist: 2.0 stop_duration_sec: 1.0 + debug: + show_stopline_collision_check: false # [-] whether to show stopline collision From b30cb9b29ee3f59f822c21c0075ef4b1b835d04b Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 25 May 2022 12:46:46 -0400 Subject: [PATCH 493/851] feat(rviz_plugin): adaptive scaling for display size (#329) Signed-off-by: Takamasa Horibe --- autoware_launch/rviz/autoware.rviz | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index c9bdce7059..5e57e3761c 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -67,12 +67,9 @@ Visualization Manager: Displays: - Class: rviz_plugins/SteeringAngle Enabled: true - Left: 128 - Length: 256 Name: SteeringAngle Scale: 17 Text Color: 25; 255; 240 - Top: 128 Topic: Depth: 5 Durability Policy: Volatile @@ -83,12 +80,9 @@ Visualization Manager: Value height offset: 0 - Class: rviz_plugins/ConsoleMeter Enabled: true - Left: 512 - Length: 256 Name: ConsoleMeter Scale: 3 Text Color: 25; 255; 240 - Top: 128 Topic: Depth: 5 Durability Policy: Volatile @@ -302,11 +296,8 @@ Visualization Manager: Wave Velocity: 40 - Class: rviz_plugins/MaxVelocity Enabled: true - Left: 595 - Length: 96 Name: MaxVelocity Text Color: 255; 255; 255 - Top: 280 Topic: Depth: 5 Durability Policy: Volatile @@ -316,10 +307,7 @@ Visualization Manager: Value: true - Class: rviz_plugins/TurnSignal Enabled: true - Height: 256 - Left: 196 Name: TurnSignal - Top: 350 Topic: Depth: 5 Durability Policy: Volatile @@ -327,7 +315,6 @@ Visualization Manager: Reliability Policy: Reliable Value: /vehicle/status/turn_indicators_status Value: true - Width: 512 Enabled: true Name: Vehicle Enabled: true From 691d54fc7dde7dd3b66f05e2c8e3075dc5c11f7a Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 26 May 2022 03:54:16 +0900 Subject: [PATCH 494/851] fix: support context dict key for humble (#328) * fix: support context dict key for humble Signed-off-by: wep21 * add todo comment Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .../ground_segmentation/ground_segmentation.launch.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index b8781ebac1..251e97dea8 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -48,8 +48,11 @@ def __init__(self, context): self.use_time_series_filter = self.ground_segmentation_param["use_time_series_filter"] def get_vehicle_info(self): - # TODO: need to rename key from "ros_params" to "global_params" after Humble + # TODO(TIER IV): Use Parameter Substitution after we drop Galactic support + # https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/substitutions/parameter.py gp = self.context.launch_configurations.get("ros_params", {}) + if not gp: + gp = self.context.launch_configurations.get("global_params", {}) p = {} p["vehicle_length"] = gp["front_overhang"] + gp["wheel_base"] + gp["rear_overhang"] p["vehicle_width"] = gp["wheel_tread"] + gp["left_overhang"] + gp["right_overhang"] From b20458634d73d3e530448daa5011e2e544e052f2 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 26 May 2022 13:33:03 +0900 Subject: [PATCH 495/851] fix: modify type of global parameter (#333) Signed-off-by: wep21 --- .../ground_segmentation/ground_segmentation.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 251e97dea8..520892e3dc 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -52,7 +52,7 @@ def get_vehicle_info(self): # https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/substitutions/parameter.py gp = self.context.launch_configurations.get("ros_params", {}) if not gp: - gp = self.context.launch_configurations.get("global_params", {}) + gp = dict(self.context.launch_configurations.get("global_params", {})) p = {} p["vehicle_length"] = gp["front_overhang"] + gp["wheel_base"] + gp["rear_overhang"] p["vehicle_width"] = gp["wheel_tread"] + gp["left_overhang"] + gp["right_overhang"] From 859e3600d8993e424ce0854b7559d6ff3cf9a33b Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sat, 28 May 2022 20:34:30 +0900 Subject: [PATCH 496/851] chore: sync files (#335) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .../build-and-test-differential.yaml | 23 +++++++++++++++---- .github/workflows/build-and-test.yaml | 23 +++++++++++++++---- 2 files changed, 36 insertions(+), 10 deletions(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 72b922a521..db998fae00 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -6,7 +6,20 @@ on: jobs: build-and-test-differential: runs-on: ubuntu-latest - container: ros:galactic + container: ${{ matrix.container }} + strategy: + fail-fast: false + matrix: + rosdistro: + - galactic + - humble + include: + - rosdistro: galactic + container: ros:galactic + build-depends-repos: build_depends.repos + - rosdistro: humble + container: ros:humble + build-depends-repos: build_depends.repos steps: - name: Cancel previous runs uses: styfle/cancel-workflow-action@0.9.1 @@ -27,18 +40,18 @@ jobs: if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} uses: autowarefoundation/autoware-github-actions/colcon-build@v1 with: - rosdistro: galactic + rosdistro: ${{ matrix.rosdistro }} target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} - build-depends-repos: build_depends.repos + build-depends-repos: ${{ matrix.build-depends-repos }} - name: Test id: test if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} uses: autowarefoundation/autoware-github-actions/colcon-test@v1 with: - rosdistro: galactic + rosdistro: ${{ matrix.rosdistro }} target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} - build-depends-repos: build_depends.repos + build-depends-repos: ${{ matrix.build-depends-repos }} - name: Upload coverage to CodeCov if: ${{ steps.test.outputs.coverage-report-files != '' }} diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 2d7ff34b79..161e3ba227 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -10,7 +10,20 @@ jobs: build-and-test: if: ${{ github.event_name != 'push' || github.ref_name == github.event.repository.default_branch }} runs-on: ubuntu-latest - container: ros:galactic + container: ${{ matrix.container }} + strategy: + fail-fast: false + matrix: + rosdistro: + - galactic + - humble + include: + - rosdistro: galactic + container: ros:galactic + build-depends-repos: build_depends.repos + - rosdistro: humble + container: ros:humble + build-depends-repos: build_depends.repos steps: - name: Check out repository uses: actions/checkout@v3 @@ -26,18 +39,18 @@ jobs: if: ${{ steps.get-self-packages.outputs.self-packages != '' }} uses: autowarefoundation/autoware-github-actions/colcon-build@v1 with: - rosdistro: galactic + rosdistro: ${{ matrix.rosdistro }} target-packages: ${{ steps.get-self-packages.outputs.self-packages }} - build-depends-repos: build_depends.repos + build-depends-repos: ${{ matrix.build-depends-repos }} - name: Test if: ${{ steps.get-self-packages.outputs.self-packages != '' }} id: test uses: autowarefoundation/autoware-github-actions/colcon-test@v1 with: - rosdistro: galactic + rosdistro: ${{ matrix.rosdistro }} target-packages: ${{ steps.get-self-packages.outputs.self-packages }} - build-depends-repos: build_depends.repos + build-depends-repos: ${{ matrix.build-depends-repos }} - name: Upload coverage to CodeCov if: ${{ steps.test.outputs.coverage-report-files != '' }} From 964f4f0b751923815c0bde043a7820246ff55b5c Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 30 May 2022 18:57:49 +0900 Subject: [PATCH 497/851] feat: use multithread for traffic light container as default (#336) Signed-off-by: tomoya.kimura --- .../launch/traffic_light_recognition/traffic_light.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 462a895420..64252eaf7c 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -38,7 +38,7 @@ - + From 5adf891769b7b6581b0d2441de3e69993aebe53a Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Wed, 1 Jun 2022 12:30:32 +0900 Subject: [PATCH 498/851] fix(localization_launch): fix input topic name (#338) --- localization_launch/launch/localization.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/localization_launch/launch/localization.launch.xml b/localization_launch/launch/localization.launch.xml index 20b29e5afe..91fbe6ac97 100644 --- a/localization_launch/launch/localization.launch.xml +++ b/localization_launch/launch/localization.launch.xml @@ -1,6 +1,6 @@ - + From d70250273f42c2e6d14881bc4ab141cfd7c5471e Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Wed, 1 Jun 2022 14:51:42 +0900 Subject: [PATCH 499/851] feat(behavior_velocity): add run out module (#339) * feat(behavior_velocity): add parameter yaml for behavior_velocity_planner Signed-off-by: Tomohito Ando * feat(behavior_velocity): add run out module Signed-off-by: Tomohito Ando * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- autoware_launch/launch/autoware.launch.xml | 5 +- .../launch/logging_simulator.launch.xml | 5 +- autoware_launch/rviz/autoware.rviz | 24 +++++ .../behavior_velocity_planner.param.yaml | 18 ++++ .../run_out.param.yaml | 45 +++++++++ planning_launch/launch/planning.launch.xml | 7 ++ .../scenario_planning/lane_driving.launch.xml | 6 ++ .../behavior_planning.launch.py | 94 ++++++++++++++----- .../behavior_planning/compare_map.launch.py | 89 ++++++++++++++++++ .../scenario_planning.launch.xml | 6 ++ 10 files changed, 274 insertions(+), 25 deletions(-) create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml create mode 100644 planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 02d6c33630..2b7bf1861f 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -78,7 +78,10 @@ - + + + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 7fc5751529..1cc48dbc85 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -94,7 +94,10 @@ - + + + + diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 5e57e3761c..e36a04c7f8 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1117,6 +1117,18 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/virtual_traffic_light Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (RunOut) + 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/virtual_wall/run_out + Value: true Enabled: true Name: VirtualWall - Class: rviz_common/Group @@ -1241,6 +1253,18 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_stopping_area Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: RunOut + 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/run_out + Value: false Enabled: false Name: DebugMarker Enabled: true diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml new file mode 100644 index 0000000000..1332e422cd --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml @@ -0,0 +1,18 @@ +/**: + ros__parameters: + launch_stop_line: true + launch_crosswalk: true + launch_traffic_light: true + launch_intersection: true + launch_blind_spot: true + launch_detection_area: true + launch_virtual_traffic_light: true + launch_occlusion_spot: true + launch_no_stopping_area: true + launch_run_out: false + forward_path_length: 1000.0 + backward_path_length: 5.0 + max_accel: -2.8 + max_jerk: -5.0 + system_delay: 0.5 + delay_response_time: 1.3 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml new file mode 100644 index 0000000000..8818ed0199 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml @@ -0,0 +1,45 @@ +/**: + ros__parameters: + run_out: + detection_method: "Object" # [-] candidate: Object, ObjectWithoutPath, Points + use_partition_lanelet: true # [-] whether to use partition lanelet map data + specify_decel_jerk: false # [-] whether to specify jerk when ego decelerates + stop_margin: 2.5 # [m] the vehicle decelerates to be able to stop with this margin + passing_margin: 1.1 # [m] the vehicle begins to accelerate if the vehicle's front in predicted position is ahead of the obstacle + this margin + deceleration_jerk: -0.3 # [m/s^3] ego decelerates with this jerk when stopping for obstacles + obstacle_velocity_kph: 5.0 # [km/h] assumption for obstacle velocity + detection_distance: 45.0 # [m] ahead distance from ego to detect the obstacles + detection_span: 1.0 # [m] calculate collision with this span to reduce calculation time + min_vel_ego_kmph: 3.6 # [km/h] min velocity to calculate time to collision + + # rectangle detection area for Points method + # this will be replaced with more appropriate detection area + detection_area_size: + dist_ahead: 50.0 # [m] ahead distance from ego position + dist_behind: 5.0 # [m] behind distance from ego position + dist_right: 7.0 # [m] right distance from ego position + dist_left: 7.0 # [m] left distance from ego position + + # parameter to create abstracted dynamic obstacles + dynamic_obstacle: + min_vel_kmph: 0.0 # [km/h] minimum velocity for dynamic obstacles + max_vel_kmph: 5.0 # [km/h] maximum velocity for dynamic obstacles + diameter: 0.1 # [m] diameter of obstacles. used for creating dynamic obstacles from points + height: 2.0 # [m] height of obstacles. used for creating dynamic obstacles from points + max_prediction_time: 10.0 # [sec] create predicted path until this time + time_step: 0.5 # [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path + + # approach if ego has stopped in the front of the obstacle for a certain amount of time + approaching: + enable: false + margin: 0.0 # [m] distance on how close ego approaches the obstacle + limit_vel_kmph: 3.0 # [km/h] limit velocity for approaching after stopping + stop_thresh: 0.01 # [m/s] threshold to decide if ego is stopping + stop_time_thresh: 3.0 # [sec] threshold for stopping time to transit to approaching state + dist_thresh: 0.5 # [m] end the approaching state if distance to the obstacle is longer than stop_margin + dist_thresh + + # parameter to avoid sudden stopping + slow_down_limit: + enable: true + max_jerk: -0.7 # [m/s^3] minimum jerk deceleration for safe brake. + max_acc : -2.0 # [m/s^2] minimum accel deceleration for safe brake. diff --git a/planning_launch/launch/planning.launch.xml b/planning_launch/launch/planning.launch.xml index 640b3a234b..f6a7abec76 100644 --- a/planning_launch/launch/planning.launch.xml +++ b/planning_launch/launch/planning.launch.xml @@ -1,5 +1,10 @@ + + + + + @@ -13,6 +18,8 @@ + + diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch.xml b/planning_launch/launch/scenario_planning/lane_driving.launch.xml index e5d4d4c6b8..ad3e351493 100644 --- a/planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving.launch.xml @@ -2,6 +2,10 @@ + + + + @@ -10,6 +14,8 @@ + + diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 8e2fe26291..9313960323 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -18,10 +18,13 @@ import launch from launch.actions import DeclareLaunchArgument from launch.actions import ExecuteProcess +from launch.actions import IncludeLaunchDescription from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition from launch.conditions import UnlessCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration +from launch.substitutions import PythonExpression from launch_ros.actions import ComposableNodeContainer from launch_ros.descriptions import ComposableNode from launch_ros.substitutions import FindPackageShare @@ -190,7 +193,7 @@ def generate_launch_description(): with open(common_param_path, "r") as f: common_param = yaml.safe_load(f)["/**"]["ros__parameters"] - base_param_path = os.path.join( + motion_velocity_smoother_param_path = os.path.join( get_package_share_directory("planning_launch"), "config", "scenario_planning", @@ -198,10 +201,10 @@ def generate_launch_description(): "motion_velocity_smoother", "motion_velocity_smoother.param.yaml", ) - with open(base_param_path, "r") as f: - base_param = yaml.safe_load(f)["/**"]["ros__parameters"] + with open(motion_velocity_smoother_param_path, "r") as f: + motion_velocity_smoother_param = yaml.safe_load(f)["/**"]["ros__parameters"] - smoother_param_path = os.path.join( + smoother_type_param_path = os.path.join( get_package_share_directory("planning_launch"), "config", "scenario_planning", @@ -209,8 +212,8 @@ def generate_launch_description(): "motion_velocity_smoother", "Analytical.param.yaml", ) - with open(smoother_param_path, "r") as f: - smoother_param = yaml.safe_load(f)["/**"]["ros__parameters"] + with open(smoother_type_param_path, "r") as f: + smoother_type_param = yaml.safe_load(f)["/**"]["ros__parameters"] # behavior velocity planner blind_spot_param_path = os.path.join( @@ -321,6 +324,30 @@ def generate_launch_description(): with open(no_stopping_area_param_path, "r") as f: no_stopping_area_param = yaml.safe_load(f)["/**"]["ros__parameters"] + run_out_param_path = os.path.join( + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", + "run_out.param.yaml", + ) + with open(run_out_param_path, "r") as f: + run_out_param = yaml.safe_load(f)["/**"]["ros__parameters"] + + behavior_velocity_planner_param_path = os.path.join( + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", + "behavior_velocity_planner.param.yaml", + ) + with open(behavior_velocity_planner_param_path, "r") as f: + behavior_velocity_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] + behavior_velocity_planner_component = ComposableNode( package="behavior_velocity_planner", plugin="behavior_velocity_planner::BehaviorVelocityPlannerNode", @@ -335,6 +362,10 @@ def generate_launch_description(): "~/input/no_ground_pointcloud", "/perception/obstacle_segmentation/pointcloud", ), + ( + "~/input/compare_map_filtered_pointcloud", + "compare_map_filtered/pointcloud", + ), ( "~/input/traffic_signals", "/perception/traffic_light_recognition/traffic_signals", @@ -361,24 +392,10 @@ def generate_launch_description(): ("~/output/traffic_signal", "debug/traffic_signal"), ], parameters=[ - { - "launch_stop_line": True, - "launch_crosswalk": True, - "launch_traffic_light": True, - "launch_intersection": True, - "launch_blind_spot": True, - "launch_detection_area": True, - "launch_virtual_traffic_light": True, - "launch_occlusion_spot": True, - "launch_no_stopping_area": True, - "forward_path_length": 1000.0, - "backward_path_length": 5.0, - "max_accel": -2.8, - "delay_response_time": 1.3, - }, + behavior_velocity_planner_param, common_param, - base_param, - smoother_param, + motion_velocity_smoother_param, + smoother_type_param, blind_spot_param, crosswalk_param, detection_area_param, @@ -388,6 +405,7 @@ def generate_launch_description(): virtual_traffic_light_param, occlusion_spot_param, no_stopping_area_param, + run_out_param, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) @@ -415,6 +433,35 @@ def generate_launch_description(): condition=IfCondition(LaunchConfiguration("use_multithread")), ) + # load compare map for run out module + load_compare_map = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + FindPackageShare("planning_launch"), + "/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py", + ] + ), + launch_arguments={ + "use_pointcloud_container": LaunchConfiguration("use_pointcloud_container"), + "container_name": LaunchConfiguration("container_name"), + "use_multithread": "true", + }.items(), + # launch compare map only when run_out module is enabled and detection method is Points + condition=IfCondition( + PythonExpression( + [ + LaunchConfiguration( + "launch_run_out", default=behavior_velocity_planner_param["launch_run_out"] + ), + " and ", + "'", + run_out_param["run_out"]["detection_method"], + "' == 'Points'", + ] + ) + ), + ) + return launch.LaunchDescription( [ DeclareLaunchArgument( @@ -426,6 +473,7 @@ def generate_launch_description(): set_container_executable, set_container_mt_executable, container, + load_compare_map, ExecuteProcess( cmd=[ "ros2", diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py new file mode 100644 index 0000000000..fe3e347fd2 --- /dev/null +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py @@ -0,0 +1,89 @@ +# Copyright 2022 TIER IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes +from launch_ros.descriptions import ComposableNode + + +def generate_launch_description(): + def add_launch_arg(name: str, default_value=None): + return DeclareLaunchArgument(name, default_value=default_value) + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + + composable_nodes = [ + ComposableNode( + package="compare_map_segmentation", + plugin="compare_map_segmentation::VoxelDistanceBasedCompareMapFilterComponent", + name="voxel_distance_based_compare_map_filter_node", + remappings=[ + ("input", "/perception/obstacle_segmentation/pointcloud"), + ("map", "/map/pointcloud_map"), + ("output", "compare_map_filtered/pointcloud"), + ], + parameters=[ + { + "distance_threshold": 0.7, + } + ], + extra_arguments=[ + {"use_intra_process_comms": False} # this node has QoS of transient local + ], + ), + ] + + compare_map_container = ComposableNodeContainer( + name=LaunchConfiguration("container_name"), + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=composable_nodes, + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), + output="screen", + ) + + load_composable_nodes = LoadComposableNodes( + composable_node_descriptions=composable_nodes, + target_container=LaunchConfiguration("container_name"), + condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), + ) + + return LaunchDescription( + [ + add_launch_arg("use_multithread", "true"), + add_launch_arg("use_pointcloud_container", "true"), + add_launch_arg("container_name", "compare_map_container"), + set_container_executable, + set_container_mt_executable, + compare_map_container, + load_composable_nodes, + ] + ) diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 5304034d27..538607f04a 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -2,6 +2,10 @@ + + + + @@ -39,6 +43,8 @@ + + From 59fc402b4fa8027cc80bfc77443c887e18a57741 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Wed, 1 Jun 2022 23:51:16 +0900 Subject: [PATCH 500/851] chore: sync awf-latest (#334) * chore: sync files (#327) Signed-off-by: GitHub Co-authored-by: kenji-miyake * refactor: virtual wall rviz config (#326) Signed-off-by: Takamasa Horibe * feat(rviz_plugin): adaptive scaling for display size (#329) Signed-off-by: Takamasa Horibe * fix: support context dict key for humble (#328) * fix: support context dict key for humble Signed-off-by: wep21 * add todo comment Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * fix: modify type of global parameter (#333) Signed-off-by: wep21 * chore: sync files (#335) Signed-off-by: GitHub Co-authored-by: kenji-miyake * feat: use multithread for traffic light container as default (#336) Signed-off-by: tomoya.kimura * fix(localization_launch): fix input topic name (#338) * feat(behavior_velocity): add run out module (#339) * feat(behavior_velocity): add parameter yaml for behavior_velocity_planner Signed-off-by: Tomohito Ando * feat(behavior_velocity): add run out module Signed-off-by: Tomohito Ando * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Co-authored-by: kenji-miyake Co-authored-by: Takamasa Horibe Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Tomoya Kimura Co-authored-by: Yamato Ando Co-authored-by: Tomohito ANDO Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../build-and-test-differential.yaml | 23 +- .github/workflows/build-and-test.yaml | 23 +- autoware_launch/launch/autoware.launch.xml | 5 +- .../launch/logging_simulator.launch.xml | 5 +- autoware_launch/rviz/autoware.rviz | 981 +++++++++--------- .../launch/localization.launch.xml | 2 +- .../ground_segmentation.launch.py | 5 +- .../traffic_light.launch.xml | 2 +- .../behavior_velocity_planner.param.yaml | 18 + .../run_out.param.yaml | 45 + planning_launch/launch/planning.launch.xml | 7 + .../scenario_planning/lane_driving.launch.xml | 6 + .../behavior_planning.launch.py | 94 +- .../behavior_planning/compare_map.launch.py | 89 ++ .../scenario_planning.launch.xml | 6 + 15 files changed, 785 insertions(+), 526 deletions(-) create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml create mode 100644 planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index b77573e096..db998fae00 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -6,7 +6,20 @@ on: jobs: build-and-test-differential: runs-on: ubuntu-latest - container: ghcr.io/autowarefoundation/autoware-universe:latest + container: ${{ matrix.container }} + strategy: + fail-fast: false + matrix: + rosdistro: + - galactic + - humble + include: + - rosdistro: galactic + container: ros:galactic + build-depends-repos: build_depends.repos + - rosdistro: humble + container: ros:humble + build-depends-repos: build_depends.repos steps: - name: Cancel previous runs uses: styfle/cancel-workflow-action@0.9.1 @@ -27,18 +40,18 @@ jobs: if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} uses: autowarefoundation/autoware-github-actions/colcon-build@v1 with: - rosdistro: galactic + rosdistro: ${{ matrix.rosdistro }} target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} - build-depends-repos: build_depends.repos + build-depends-repos: ${{ matrix.build-depends-repos }} - name: Test id: test if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} uses: autowarefoundation/autoware-github-actions/colcon-test@v1 with: - rosdistro: galactic + rosdistro: ${{ matrix.rosdistro }} target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} - build-depends-repos: build_depends.repos + build-depends-repos: ${{ matrix.build-depends-repos }} - name: Upload coverage to CodeCov if: ${{ steps.test.outputs.coverage-report-files != '' }} diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index f0760d99ae..161e3ba227 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -10,7 +10,20 @@ jobs: build-and-test: if: ${{ github.event_name != 'push' || github.ref_name == github.event.repository.default_branch }} runs-on: ubuntu-latest - container: ghcr.io/autowarefoundation/autoware-universe:latest + container: ${{ matrix.container }} + strategy: + fail-fast: false + matrix: + rosdistro: + - galactic + - humble + include: + - rosdistro: galactic + container: ros:galactic + build-depends-repos: build_depends.repos + - rosdistro: humble + container: ros:humble + build-depends-repos: build_depends.repos steps: - name: Check out repository uses: actions/checkout@v3 @@ -26,18 +39,18 @@ jobs: if: ${{ steps.get-self-packages.outputs.self-packages != '' }} uses: autowarefoundation/autoware-github-actions/colcon-build@v1 with: - rosdistro: galactic + rosdistro: ${{ matrix.rosdistro }} target-packages: ${{ steps.get-self-packages.outputs.self-packages }} - build-depends-repos: build_depends.repos + build-depends-repos: ${{ matrix.build-depends-repos }} - name: Test if: ${{ steps.get-self-packages.outputs.self-packages != '' }} id: test uses: autowarefoundation/autoware-github-actions/colcon-test@v1 with: - rosdistro: galactic + rosdistro: ${{ matrix.rosdistro }} target-packages: ${{ steps.get-self-packages.outputs.self-packages }} - build-depends-repos: build_depends.repos + build-depends-repos: ${{ matrix.build-depends-repos }} - name: Upload coverage to CodeCov if: ${{ steps.test.outputs.coverage-report-files != '' }} diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 02d6c33630..2b7bf1861f 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -78,7 +78,10 @@ - + + + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 7fc5751529..1cc48dbc85 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -94,7 +94,10 @@ - + + + + diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 690e038e7a..e36a04c7f8 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -42,8 +42,7 @@ Visualization Manager: Show Arrows: true Show Axes: true Show Names: true - Tree: - {} + Tree: {} Update Interval: 0 Value: false - Alpha: 0.5 @@ -68,12 +67,9 @@ Visualization Manager: Displays: - Class: rviz_plugins/SteeringAngle Enabled: true - Left: 128 - Length: 256 Name: SteeringAngle Scale: 17 Text Color: 25; 255; 240 - Top: 128 Topic: Depth: 5 Durability Policy: Volatile @@ -84,12 +80,9 @@ Visualization Manager: Value height offset: 0 - Class: rviz_plugins/ConsoleMeter Enabled: true - Left: 512 - Length: 256 Name: ConsoleMeter Scale: 3 Text Color: 25; 255; 240 - Top: 128 Topic: Depth: 5 Durability Policy: Volatile @@ -303,11 +296,8 @@ Visualization Manager: Wave Velocity: 40 - Class: rviz_plugins/MaxVelocity Enabled: true - Left: 595 - Length: 96 Name: MaxVelocity Text Color: 255; 255; 255 - Top: 280 Topic: Depth: 5 Durability Policy: Volatile @@ -317,10 +307,7 @@ Visualization Manager: Value: true - Class: rviz_plugins/TurnSignal Enabled: true - Height: 256 - Left: 196 Name: TurnSignal - Top: 350 Topic: Depth: 5 Durability Policy: Volatile @@ -328,7 +315,6 @@ Visualization Manager: Reliability Policy: Reliable Value: /vehicle/status/turn_indicators_status Value: true - Width: 512 Enabled: true Name: Vehicle Enabled: true @@ -650,8 +636,7 @@ Visualization Manager: - Class: rviz_default_plugins/MarkerArray Enabled: true Name: MonteCarloInitialPose - Namespaces: - {} + Namespaces: {} Topic: Depth: 5 Durability Policy: Volatile @@ -724,207 +709,174 @@ Visualization Manager: Name: Segmentation - Class: rviz_common/Group Displays: - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/DetectedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true - Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: DetectedObjects - Namespaces: - {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/detection/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 - Value: true - Enabled: false - Name: Detection - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/TrackedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true - Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: TrackedObjects - Namespaces: - {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/tracking/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 - Value: true - Enabled: false - Name: Tracking - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/PredictedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true - Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: PredictedObjects - Namespaces: - {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 - Value: true + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true Enabled: true - Name: Prediction - Enabled: true - Name: ObjectRecognition + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: DetectedObjects + Namespaces: {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/object_recognition/detection/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 + Value: true + Enabled: false + Name: Detection - Class: rviz_common/Group Displays: - - Class: rviz_default_plugins/Image + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/TrackedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true Enabled: true - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: RecognitionResultOnImage - Normalize Range: true + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: TrackedObjects + Namespaces: {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/traffic_light_recognition/debug/rois + Value: /perception/object_recognition/tracking/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 Value: true - - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Tracking + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/PredictedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: false + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: false + Display UUID: true + Display Velocity: true Enabled: true - Name: MapBasedDetectionResult - Namespaces: - {} + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: PredictedObjects + Namespaces: {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers + Value: /perception/object_recognition/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 Value: true Enabled: true - Name: TrafficLight + Name: Prediction - Class: rviz_common/Group Displays: - - Alpha: 0.5 - Class: rviz_default_plugins/Map - Color Scheme: map - Draw Behind: false + - Class: rviz_default_plugins/Image Enabled: true - Name: Map + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: RecognitionResultOnImage + Normalize Range: true Topic: Depth: 5 Durability Policy: Volatile - Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/occupancy_grid_map/map - Update Topic: + Value: /perception/traffic_light_recognition/debug/rois + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: MapBasedDetectionResult + Namespaces: {} + Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /perception/occupancy_grid_map/map_updates - Use Timestamp: false + Value: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers Value: true - Enabled: false - Name: OccupancyGrid + Enabled: true + Name: TrafficLight Enabled: true Name: Perception - Class: rviz_common/Group @@ -1019,201 +971,6 @@ Visualization Manager: Constant Color: false Scale: 0.30000001192092896 Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Arrow - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Crosswalk - Namespaces: - collision line: false - collision point: false - factor_text: true - slow factor_text: true - slow point: false - slow polygon line: false - slow virtual_wall: true - stop point: false - stop polygon line: false - stop_virtual_wall: true - walkway stop judge range: false - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Intersection - Namespaces: - candidate_collision_ego_lane_polygon: false - candidate_collision_object_polygons: false - conflicting_targets: false - detection_area: false - ego_lane: false - factor_text: true - judge_point_pose_line: false - path_raw: false - spline: false - stop_point_pose_line: false - stop_virtual_wall: true - stuck_vehicle_detect_area: false - stuck_targets: false - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: MergeFromPrivate - Namespaces: - factor_text: true - stop_point_pose_line: false - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/merge_from_private - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Blind Spot - Namespaces: - conflict_area_for_blind_spot: false - conflicting_targets: false - detection_area: false - detection_area_for_blind_spot: false - factor_text: true - judge_point_pose_line: false - path_raw: false - stop_virtual_wall: true - spline: false - stop_point_pose_line: false - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/blind_spot - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: TrafficLight - Namespaces: - dead line factor_text: false - dead line virtual_wall: false - factor_text: true - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/traffic_light - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualTrafficLight - Namespaces: - end_lines: false - instrument_center: false - instrument_id: false - start_line: false - stop_factor_text: true - stop_line: false - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/virtual_traffic_light - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: StopLine - Namespaces: - factor_text: true - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/stop_line - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: DetectionArea - Namespaces: - detection_area_correspondence: false - detection_area_id: false - detection_area_polygon: false - factor_text: true - obstacles: false - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: OcclusionSpot - Namespaces: - arrow: false - occlusion spot slow down: true - collision: false - info_obstacle: false - obstacle: false - detection_area: false - slow factor_text: true - path_raw: false - path_interpolated: false - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/occlusion_spot - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: NoStoppingArea - Namespaces: - no_stopping_area_correspondence: false - no_stopping_area_id: false - no_stopping_area_polygon: false - stuck_vehicle_detect_area: false - stop_line_detect_area: false - stuck_points: false - stop_factor_text: true - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_stopping_area - Value: true - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true @@ -1237,18 +994,279 @@ Visualization Manager: Constant Color: false Scale: 0.30000001192092896 Value: false - - Class: rviz_default_plugins/MarkerArray + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (BlindSpot) + 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/virtual_wall/blind_spot + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (Crosswalk) + 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/virtual_wall/crosswalk + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (DetectionArea) + 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/virtual_wall/detection_area + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (Intersection) + 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/virtual_wall/intersection + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (MergeFromPrivateArea) + 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/virtual_wall/merge_from_private + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (NoStoppingArea) + 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/virtual_wall/no_stopping_area + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (OcclusionSpot) + 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/virtual_wall/occlusion_spot + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (StopLine) + Namespaces: + stop_factor_text: true + stop_virtual_wall: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/stop_line + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (TrafficLight) + 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/virtual_wall/traffic_light + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (VirtualTrafficLight) + 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/virtual_wall/virtual_traffic_light + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (RunOut) + 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/virtual_wall/run_out + Value: true + Enabled: true + Name: VirtualWall + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Arrow + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Crosswalk + 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/crosswalk + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Intersection + 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/intersection + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Blind Spot + 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/blind_spot + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: TrafficLight + 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/traffic_light + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: VirtualTrafficLight + 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/virtual_traffic_light + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: StopLine + 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/stop_line + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: DetectionArea + 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/detection_area + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: OcclusionSpot + 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/occlusion_spot + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: NoStoppingArea + 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/no_stopping_area + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: RunOut + 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/run_out + Value: false Enabled: false - Name: DrivableAreaBoundary - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_boundary - Value: true + Name: DebugMarker Enabled: true Name: BehaviorPlanning - Class: rviz_common/Group @@ -1276,81 +1294,86 @@ Visualization Manager: Constant Color: false Scale: 0.30000001192092896 Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: ObstacleStop - Namespaces: - collision_polygons: false - detection_polygons: false - slow_down_polygons: false - slow_down_detection_polygons: false - stop_obstacle_point: false - stop_obstacle_text: false - slow_down_obstacle_point: false - slow_down_obstacle_text: false - slow_down_start_virtual_wall: false - slow_down_start_factor_text: false - slow_down_end_virtual_wall: false - slow_down_end_factor_text: false - slow_down_end: false - stop_virtual_wall: true - stop_factor_text: true - slow_down_virtual_wall: true - slow_down_factor_text: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker - Value: true - - Class: rviz_default_plugins/MarkerArray + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (ObstacleStop) + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/virtual_wall + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (SurroundObstacle) + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/virtual_wall + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (ObstacleAvoidance) + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/wall_marker + Value: true Enabled: true - Name: SurroundObstacleCheck - Namespaces: - factor_text: true - virtual_wall: true - obstacle_point: true - no_start_obstacle_text: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: ObstacleAvoidance - Namespaces: - base_bounds_0: false - base_bounds_1: false - base_bounds_2: false - current_vehicle_circles: false - lateral_errors: false - mpt_footprints: false - vehicle_circle_lines: false - vehicle_circles: false - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: ObstacleAvoidanceWall - Namespaces: - virtual_wall: true - virtual_wall_text: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/wall_marker - Value: true + Name: VirtualWall + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: ObstacleStop + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: SurroundObstacleCheck + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: ObstacleAvoidance + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker + Value: true + Enabled: false + Name: DebugMarker Enabled: true Name: MotionPlanning Enabled: true @@ -1419,22 +1442,6 @@ Visualization Manager: Value: true Enabled: true Name: Parking - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: TrajectoryErrorMarker - Namespaces: - trajectory_relative_angle: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/planning_diagnostics/planning_error_monitor/debug/marker - Value: true - Enabled: true - Name: PlanningDiagnostics Enabled: true Name: ScenarioPlanning Enabled: true @@ -1467,8 +1474,7 @@ Visualization Manager: - Class: rviz_default_plugins/MarkerArray Enabled: false Name: Debug/MPC - Namespaces: - {} + Namespaces: {} Topic: Depth: 5 Durability Policy: Volatile @@ -1479,14 +1485,13 @@ Visualization Manager: - Class: rviz_default_plugins/MarkerArray Enabled: false Name: Debug/PurePursuit - Namespaces: - {} + Namespaces: {} Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /control/trajectory_follower/pure_pursuit_node_exe/debug/markers + Value: /control/trajectory_follower/pure_pursuit/debug/markers Value: false Enabled: true Name: Control diff --git a/localization_launch/launch/localization.launch.xml b/localization_launch/launch/localization.launch.xml index 20b29e5afe..91fbe6ac97 100644 --- a/localization_launch/launch/localization.launch.xml +++ b/localization_launch/launch/localization.launch.xml @@ -1,6 +1,6 @@ - + diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index b8781ebac1..520892e3dc 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -48,8 +48,11 @@ def __init__(self, context): self.use_time_series_filter = self.ground_segmentation_param["use_time_series_filter"] def get_vehicle_info(self): - # TODO: need to rename key from "ros_params" to "global_params" after Humble + # TODO(TIER IV): Use Parameter Substitution after we drop Galactic support + # https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/substitutions/parameter.py gp = self.context.launch_configurations.get("ros_params", {}) + if not gp: + gp = dict(self.context.launch_configurations.get("global_params", {})) p = {} p["vehicle_length"] = gp["front_overhang"] + gp["wheel_base"] + gp["rear_overhang"] p["vehicle_width"] = gp["wheel_tread"] + gp["left_overhang"] + gp["right_overhang"] 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 462a895420..64252eaf7c 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -38,7 +38,7 @@ - + diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml new file mode 100644 index 0000000000..1332e422cd --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml @@ -0,0 +1,18 @@ +/**: + ros__parameters: + launch_stop_line: true + launch_crosswalk: true + launch_traffic_light: true + launch_intersection: true + launch_blind_spot: true + launch_detection_area: true + launch_virtual_traffic_light: true + launch_occlusion_spot: true + launch_no_stopping_area: true + launch_run_out: false + forward_path_length: 1000.0 + backward_path_length: 5.0 + max_accel: -2.8 + max_jerk: -5.0 + system_delay: 0.5 + delay_response_time: 1.3 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml new file mode 100644 index 0000000000..8818ed0199 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml @@ -0,0 +1,45 @@ +/**: + ros__parameters: + run_out: + detection_method: "Object" # [-] candidate: Object, ObjectWithoutPath, Points + use_partition_lanelet: true # [-] whether to use partition lanelet map data + specify_decel_jerk: false # [-] whether to specify jerk when ego decelerates + stop_margin: 2.5 # [m] the vehicle decelerates to be able to stop with this margin + passing_margin: 1.1 # [m] the vehicle begins to accelerate if the vehicle's front in predicted position is ahead of the obstacle + this margin + deceleration_jerk: -0.3 # [m/s^3] ego decelerates with this jerk when stopping for obstacles + obstacle_velocity_kph: 5.0 # [km/h] assumption for obstacle velocity + detection_distance: 45.0 # [m] ahead distance from ego to detect the obstacles + detection_span: 1.0 # [m] calculate collision with this span to reduce calculation time + min_vel_ego_kmph: 3.6 # [km/h] min velocity to calculate time to collision + + # rectangle detection area for Points method + # this will be replaced with more appropriate detection area + detection_area_size: + dist_ahead: 50.0 # [m] ahead distance from ego position + dist_behind: 5.0 # [m] behind distance from ego position + dist_right: 7.0 # [m] right distance from ego position + dist_left: 7.0 # [m] left distance from ego position + + # parameter to create abstracted dynamic obstacles + dynamic_obstacle: + min_vel_kmph: 0.0 # [km/h] minimum velocity for dynamic obstacles + max_vel_kmph: 5.0 # [km/h] maximum velocity for dynamic obstacles + diameter: 0.1 # [m] diameter of obstacles. used for creating dynamic obstacles from points + height: 2.0 # [m] height of obstacles. used for creating dynamic obstacles from points + max_prediction_time: 10.0 # [sec] create predicted path until this time + time_step: 0.5 # [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path + + # approach if ego has stopped in the front of the obstacle for a certain amount of time + approaching: + enable: false + margin: 0.0 # [m] distance on how close ego approaches the obstacle + limit_vel_kmph: 3.0 # [km/h] limit velocity for approaching after stopping + stop_thresh: 0.01 # [m/s] threshold to decide if ego is stopping + stop_time_thresh: 3.0 # [sec] threshold for stopping time to transit to approaching state + dist_thresh: 0.5 # [m] end the approaching state if distance to the obstacle is longer than stop_margin + dist_thresh + + # parameter to avoid sudden stopping + slow_down_limit: + enable: true + max_jerk: -0.7 # [m/s^3] minimum jerk deceleration for safe brake. + max_acc : -2.0 # [m/s^2] minimum accel deceleration for safe brake. diff --git a/planning_launch/launch/planning.launch.xml b/planning_launch/launch/planning.launch.xml index 640b3a234b..f6a7abec76 100644 --- a/planning_launch/launch/planning.launch.xml +++ b/planning_launch/launch/planning.launch.xml @@ -1,5 +1,10 @@ + + + + + @@ -13,6 +18,8 @@ + + diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch.xml b/planning_launch/launch/scenario_planning/lane_driving.launch.xml index e5d4d4c6b8..ad3e351493 100644 --- a/planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving.launch.xml @@ -2,6 +2,10 @@ + + + + @@ -10,6 +14,8 @@ + + diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 8e2fe26291..9313960323 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -18,10 +18,13 @@ import launch from launch.actions import DeclareLaunchArgument from launch.actions import ExecuteProcess +from launch.actions import IncludeLaunchDescription from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition from launch.conditions import UnlessCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration +from launch.substitutions import PythonExpression from launch_ros.actions import ComposableNodeContainer from launch_ros.descriptions import ComposableNode from launch_ros.substitutions import FindPackageShare @@ -190,7 +193,7 @@ def generate_launch_description(): with open(common_param_path, "r") as f: common_param = yaml.safe_load(f)["/**"]["ros__parameters"] - base_param_path = os.path.join( + motion_velocity_smoother_param_path = os.path.join( get_package_share_directory("planning_launch"), "config", "scenario_planning", @@ -198,10 +201,10 @@ def generate_launch_description(): "motion_velocity_smoother", "motion_velocity_smoother.param.yaml", ) - with open(base_param_path, "r") as f: - base_param = yaml.safe_load(f)["/**"]["ros__parameters"] + with open(motion_velocity_smoother_param_path, "r") as f: + motion_velocity_smoother_param = yaml.safe_load(f)["/**"]["ros__parameters"] - smoother_param_path = os.path.join( + smoother_type_param_path = os.path.join( get_package_share_directory("planning_launch"), "config", "scenario_planning", @@ -209,8 +212,8 @@ def generate_launch_description(): "motion_velocity_smoother", "Analytical.param.yaml", ) - with open(smoother_param_path, "r") as f: - smoother_param = yaml.safe_load(f)["/**"]["ros__parameters"] + with open(smoother_type_param_path, "r") as f: + smoother_type_param = yaml.safe_load(f)["/**"]["ros__parameters"] # behavior velocity planner blind_spot_param_path = os.path.join( @@ -321,6 +324,30 @@ def generate_launch_description(): with open(no_stopping_area_param_path, "r") as f: no_stopping_area_param = yaml.safe_load(f)["/**"]["ros__parameters"] + run_out_param_path = os.path.join( + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", + "run_out.param.yaml", + ) + with open(run_out_param_path, "r") as f: + run_out_param = yaml.safe_load(f)["/**"]["ros__parameters"] + + behavior_velocity_planner_param_path = os.path.join( + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", + "behavior_velocity_planner.param.yaml", + ) + with open(behavior_velocity_planner_param_path, "r") as f: + behavior_velocity_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] + behavior_velocity_planner_component = ComposableNode( package="behavior_velocity_planner", plugin="behavior_velocity_planner::BehaviorVelocityPlannerNode", @@ -335,6 +362,10 @@ def generate_launch_description(): "~/input/no_ground_pointcloud", "/perception/obstacle_segmentation/pointcloud", ), + ( + "~/input/compare_map_filtered_pointcloud", + "compare_map_filtered/pointcloud", + ), ( "~/input/traffic_signals", "/perception/traffic_light_recognition/traffic_signals", @@ -361,24 +392,10 @@ def generate_launch_description(): ("~/output/traffic_signal", "debug/traffic_signal"), ], parameters=[ - { - "launch_stop_line": True, - "launch_crosswalk": True, - "launch_traffic_light": True, - "launch_intersection": True, - "launch_blind_spot": True, - "launch_detection_area": True, - "launch_virtual_traffic_light": True, - "launch_occlusion_spot": True, - "launch_no_stopping_area": True, - "forward_path_length": 1000.0, - "backward_path_length": 5.0, - "max_accel": -2.8, - "delay_response_time": 1.3, - }, + behavior_velocity_planner_param, common_param, - base_param, - smoother_param, + motion_velocity_smoother_param, + smoother_type_param, blind_spot_param, crosswalk_param, detection_area_param, @@ -388,6 +405,7 @@ def generate_launch_description(): virtual_traffic_light_param, occlusion_spot_param, no_stopping_area_param, + run_out_param, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) @@ -415,6 +433,35 @@ def generate_launch_description(): condition=IfCondition(LaunchConfiguration("use_multithread")), ) + # load compare map for run out module + load_compare_map = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + FindPackageShare("planning_launch"), + "/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py", + ] + ), + launch_arguments={ + "use_pointcloud_container": LaunchConfiguration("use_pointcloud_container"), + "container_name": LaunchConfiguration("container_name"), + "use_multithread": "true", + }.items(), + # launch compare map only when run_out module is enabled and detection method is Points + condition=IfCondition( + PythonExpression( + [ + LaunchConfiguration( + "launch_run_out", default=behavior_velocity_planner_param["launch_run_out"] + ), + " and ", + "'", + run_out_param["run_out"]["detection_method"], + "' == 'Points'", + ] + ) + ), + ) + return launch.LaunchDescription( [ DeclareLaunchArgument( @@ -426,6 +473,7 @@ def generate_launch_description(): set_container_executable, set_container_mt_executable, container, + load_compare_map, ExecuteProcess( cmd=[ "ros2", diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py new file mode 100644 index 0000000000..fe3e347fd2 --- /dev/null +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py @@ -0,0 +1,89 @@ +# Copyright 2022 TIER IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes +from launch_ros.descriptions import ComposableNode + + +def generate_launch_description(): + def add_launch_arg(name: str, default_value=None): + return DeclareLaunchArgument(name, default_value=default_value) + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + + composable_nodes = [ + ComposableNode( + package="compare_map_segmentation", + plugin="compare_map_segmentation::VoxelDistanceBasedCompareMapFilterComponent", + name="voxel_distance_based_compare_map_filter_node", + remappings=[ + ("input", "/perception/obstacle_segmentation/pointcloud"), + ("map", "/map/pointcloud_map"), + ("output", "compare_map_filtered/pointcloud"), + ], + parameters=[ + { + "distance_threshold": 0.7, + } + ], + extra_arguments=[ + {"use_intra_process_comms": False} # this node has QoS of transient local + ], + ), + ] + + compare_map_container = ComposableNodeContainer( + name=LaunchConfiguration("container_name"), + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=composable_nodes, + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), + output="screen", + ) + + load_composable_nodes = LoadComposableNodes( + composable_node_descriptions=composable_nodes, + target_container=LaunchConfiguration("container_name"), + condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), + ) + + return LaunchDescription( + [ + add_launch_arg("use_multithread", "true"), + add_launch_arg("use_pointcloud_container", "true"), + add_launch_arg("container_name", "compare_map_container"), + set_container_executable, + set_container_mt_executable, + compare_map_container, + load_composable_nodes, + ] + ) diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 5304034d27..538607f04a 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -2,6 +2,10 @@ + + + + @@ -39,6 +43,8 @@ + + From 06f3739b1852678158062a4d4663967e7dde25f9 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Sun, 5 Jun 2022 00:28:32 +0900 Subject: [PATCH 501/851] fix(mission_planner): disable lane_start_bound in Rviz (#341) Signed-off-by: h-ohta --- autoware_launch/rviz/autoware.rviz | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index e36a04c7f8..33c099958f 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -888,6 +888,7 @@ Visualization Manager: Name: RouteArea Namespaces: goal_lanelets: true + lane_start_bound: false left_lane_bound: false right_lane_bound: false route_lanelets: true From 0140b8c8da1beb6a3a897df62f868ebf4f1b39fe Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 6 Jun 2022 16:59:55 +0900 Subject: [PATCH 502/851] feat(planning_launch): add obstacle_cruise_planner (#330) * feat(planning_launch): add obstacle_velocity_planner Signed-off-by: Takayuki Murooka * We can select obsatcle_velocity and obstacle_stop with option Signed-off-by: Takayuki Murooka * update params Signed-off-by: Takayuki Murooka * use obstacle_stop by default Signed-off-by: Takayuki Murooka * use cruise_stop_planner option Signed-off-by: Takayuki Murooka * obstacle_velocity -> adaptive_cruise Signed-off-by: Takayuki Murooka * add min_ego_accel_for_rss Signed-off-by: Takayuki Murooka * rename to obstacle_cruise_planner Signed-off-by: Takayuki Murooka * fix review Signed-off-by: Takayuki Murooka * Update autoware_launch/rviz/autoware.rviz Co-authored-by: Yukihiro Saito Co-authored-by: Yukihiro Saito --- autoware_launch/rviz/autoware.rviz | 40 ++++++ .../obstacle_cruise_planner.param.yaml | 123 ++++++++++++++++++ .../motion_planning/motion_planning.launch.py | 72 +++++++++- 3 files changed, 234 insertions(+), 1 deletion(-) create mode 100644 planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index e36a04c7f8..75e9a28ef6 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1332,6 +1332,18 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/wall_marker Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (ObstacleCruise) + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/virtual_wall + Value: true Enabled: true Name: VirtualWall - Class: rviz_common/Group @@ -1348,6 +1360,34 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker Value: true + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: CruiseVirtualWall + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/cruise_wall_marker + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: DebugMarker + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/marker + Value: true + Enabled: true + Name: ObstacleCruise - Class: rviz_default_plugins/MarkerArray Enabled: true Name: SurroundObstacleCheck diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml new file mode 100644 index 0000000000..32af994e49 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -0,0 +1,123 @@ +/**: + ros__parameters: + common: + planning_algorithm: "pid_base" # currently supported algorithm is "pid_base" + + is_showing_debug_info: true + + # longitudinal info + idling_time: 4.0 # idling time to detect front vehicle starting deceleration [s] + min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] + min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] + safe_distance_margin : 6.0 # This is also used as a stop margin [m] + min_strong_accel: -3.0 # obstacle stop requiring deceleration less than this value will be ignored [m/ss] + + lpf_gain_for_accel: 0.2 # gain of low pass filter for ego acceleration [-] + + nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index + nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index + min_behavior_stop_margin: 3.0 # [m] + + cruise_obstacle_type: + unknown: true + car: true + truck: true + bus: true + trailer: true + motorcycle: true + bicycle: false + pedestrian: false + + stop_obstacle_type: + unknown: true + car: true + truck: true + bus: true + trailer: true + motorcycle: true + bicycle: true + pedestrian: true + + obstacle_filtering: + rough_detection_area_expand_width : 5.0 # rough lateral margin for rough detection area expansion [m] + detection_area_expand_width : 0.0 # lateral margin for precise detection area expansion + decimate_trajectory_step_length : 2.0 # longitudinal step length to calculate trajectory polygon for collision checking + + # if crossing vehicle is decided as target obstacles or not + crossing_obstacle_velocity_threshold : 3.0 # velocity threshold for crossing obstacle for cruise or stop [m/s] + crossing_obstacle_traj_angle_threshold : 1.22 # [rad] = 70 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop + collision_time_margin : 8.0 # time threshold of collision between obstacle adn ego for cruise or stop [s] + + ego_obstacle_overlap_time_threshold : 1.0 # time threshold to decide cut-in obstacle for cruise or stop [s] + max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego + + ignored_outside_obstacle_type: + unknown: false + car: false + truck: false + bus: false + trailer: false + motorcycle: false + bicycle: true + pedestrian: true + + pid_based_planner: + # use_predicted_obstacle_pose: false + + # PID gains to keep safe distance with the front vehicle + kp: 0.6 + ki: 0.0 + kd: 0.5 + + min_accel_during_cruise: -2.0 # minimum acceleration during cruise to slow down [m/ss] + + output_ratio_during_accel: 2.5 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-] + vel_to_acc_weight: 8.0 # target acceleration is calculated by (target_velocity - current_velocity) * vel_to_acc_weight [-] + + min_cruise_target_vel: 0.0 # minimum target velocity during slow down [m/s] + + obstacle_velocity_threshold_from_cruise_to_stop : 3.0 # stop planning is executed to the obstacle whose velocity is less than this value [m/s] + + optimization_based_planner: + limit_min_accel: -3.0 + resampling_s_interval: 2.0 + dense_resampling_time_interval: 0.1 + sparse_resampling_time_interval: 1.0 + dense_time_horizon: 5.0 + max_time_horizon: 25.0 + max_trajectory_length: 200.0 + velocity_margin: 0.1 #[m/s] + + # Parameters for safe distance + safe_distance_margin: 5.0 + t_dangerous: 0.5 + + # Parameters for collision detection + collision_time_threshold: 10.0 + object_zero_velocity_threshold: 3.0 #[m/s] + object_low_velocity_threshold: 3.0 #[m/s] + external_velocity_limit: 20.0 #[m/s] + delta_yaw_threshold_of_object_and_ego: 90.0 # [deg] + delta_yaw_threshold_of_nearest_index: 60.0 # [deg] + collision_duration_threshold_of_object_and_ego: 1.0 # [s] + + # Switch for each functions + enable_adaptive_cruise: true + use_object_acceleration: false + use_hd_map: true + + # For initial Motion + replan_vel_deviation: 5.0 # 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 planning 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] + + # Weights for optimization + max_s_weight: 100.0 + max_v_weight: 1.0 + over_s_safety_weight: 1000000.0 + over_s_ideal_weight: 50.0 + over_v_weight: 500000.0 + over_a_weight: 5000.0 + over_j_weight: 10000.0 diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index 2df9795b84..4c341a0670 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -19,6 +19,7 @@ from launch.actions import DeclareLaunchArgument from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition +from launch.conditions import LaunchConfigurationEquals from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer @@ -107,6 +108,39 @@ def generate_launch_description(): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + # obstacle cruise planner + obstacle_cruise_planner_param_path = os.path.join( + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "motion_planning", + "obstacle_cruise_planner", + "obstacle_cruise_planner.param.yaml", + ) + with open(obstacle_cruise_planner_param_path, "r") as f: + obstacle_cruise_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] + obstacle_cruise_planner_component = ComposableNode( + package="obstacle_cruise_planner", + plugin="motion_planning::ObstacleCruisePlannerNode", + name="obstacle_cruise_planner", + namespace="", + remappings=[ + ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), + ("~/input/odometry", "/localization/kinematic_state"), + ("~/input/objects", "/perception/object_recognition/objects"), + ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), + ("~/output/velocity_limit", "/planning/scenario_planning/max_velocity_candidates"), + ("~/output/clear_velocity_limit", "/planning/scenario_planning/clear_velocity_limit"), + ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), + ], + parameters=[ + common_param, + obstacle_cruise_planner_param, + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + # obstacle stop planner obstacle_stop_planner_param_path = os.path.join( get_package_share_directory("planning_launch"), @@ -161,6 +195,19 @@ def generate_launch_description(): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + obstacle_cruise_planner_relay_component = ComposableNode( + package="topic_tools", + plugin="topic_tools::RelayNode", + name="obstacle_cruise_planner_relay", + namespace="", + parameters=[ + {"input_topic": "obstacle_avoidance_planner/trajectory"}, + {"output_topic": "/planning/scenario_planning/lane_driving/trajectory"}, + {"type": "autoware_auto_planning_msgs/msg/Trajectory"}, + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + container = ComposableNodeContainer( name="motion_planning_container", namespace="", @@ -168,10 +215,27 @@ def generate_launch_description(): executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ obstacle_avoidance_planner_component, - obstacle_stop_planner_component, ], ) + obstacle_stop_planner_loader = LoadComposableNodes( + composable_node_descriptions=[obstacle_stop_planner_component], + target_container=container, + condition=LaunchConfigurationEquals("cruise_planner", "obstacle_stop_planner"), + ) + + obstacle_cruise_planner_loader = LoadComposableNodes( + composable_node_descriptions=[obstacle_cruise_planner_component], + target_container=container, + condition=LaunchConfigurationEquals("cruise_planner", "obstacle_cruise_planner"), + ) + + obstacle_cruise_planner_relay_loader = LoadComposableNodes( + composable_node_descriptions=[obstacle_cruise_planner_relay_component], + target_container=container, + condition=LaunchConfigurationEquals("cruise_planner", "none"), + ) + surround_obstacle_checker_loader = LoadComposableNodes( composable_node_descriptions=[surround_obstacle_checker_component], target_container=container, @@ -196,11 +260,17 @@ def generate_launch_description(): default_value="/planning/scenario_planning/lane_driving/behavior_planning/path", ), DeclareLaunchArgument("use_surround_obstacle_check", default_value="true"), + DeclareLaunchArgument( + "cruise_planner", default_value="obstacle_stop_planner" + ), # select from "obstacle_stop_planner", "obstacle_cruise_planner", "none" DeclareLaunchArgument("use_intra_process", default_value="false"), DeclareLaunchArgument("use_multithread", default_value="false"), set_container_executable, set_container_mt_executable, container, surround_obstacle_checker_loader, + obstacle_stop_planner_loader, + obstacle_cruise_planner_loader, + obstacle_cruise_planner_relay_loader, ] ) From 158fd77d81449379c6854a784c1e52f6c22ae1bb Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 6 Jun 2022 18:50:23 +0900 Subject: [PATCH 503/851] fix(autoware_launch): fix rviz indent (#342) Signed-off-by: Takayuki Murooka --- 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 75e9a28ef6..4d59ac9b1d 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1342,7 +1342,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/virtual_wall + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/virtual_wall Value: true Enabled: true Name: VirtualWall From 208743aebc9ad243fc79a633812639a9f0aecf58 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Tue, 7 Jun 2022 20:22:28 +0900 Subject: [PATCH 504/851] feat(planning_launch): launch rtc_auto_approver (#343) Signed-off-by: Fumiya Watanabe --- .../rtc_auto_approver.param.yaml | 29 +++++++++++++++++++ .../scenario_planning/lane_driving.launch.xml | 4 +++ 2 files changed, 33 insertions(+) create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_approver/rtc_auto_approver.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_approver/rtc_auto_approver.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_approver/rtc_auto_approver.param.yaml new file mode 100644 index 0000000000..5b98c1c070 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_approver/rtc_auto_approver.param.yaml @@ -0,0 +1,29 @@ +/**: + ros__parameters: + module_list: + - "behavior_velocity_planner/blind_spot" + - "behavior_velocity_planner/crosswalk" + - "behavior_velocity_planner/detection_area" + - "behavior_velocity_planner/intersection" + - "behavior_velocity_planner/no_stopping_area" + - "behavior_velocity_planner/traffic_light" + - "behavior_path_planner/lane_change_left" + - "behavior_path_planner/lane_change_right" + - "behavior_path_planner/avoidance_left" + - "behavior_path_planner/avoidance_right" + - "behavior_path_planner/pull_over" + - "behavior_path_planner/pull_out" + + default_enable_list: + - "behavior_velocity_planner/blind_spot" + - "behavior_velocity_planner/crosswalk" + - "behavior_velocity_planner/detection_area" + - "behavior_velocity_planner/intersection" + - "behavior_velocity_planner/no_stopping_area" + - "behavior_velocity_planner/traffic_light" + - "behavior_path_planner/lane_change_left" + - "behavior_path_planner/lane_change_right" + - "behavior_path_planner/avoidance_left" + - "behavior_path_planner/avoidance_right" + - "behavior_path_planner/pull_over" + - "behavior_path_planner/pull_out" diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch.xml b/planning_launch/launch/scenario_planning/lane_driving.launch.xml index ad3e351493..a0e35c5874 100644 --- a/planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving.launch.xml @@ -17,6 +17,10 @@ + + + + From 981b5526aea6f01b2f621e164d9d30c40c7e4967 Mon Sep 17 00:00:00 2001 From: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Date: Thu, 9 Jun 2022 13:08:43 +0900 Subject: [PATCH 505/851] feat(intersection_module): add right and left margin parameter (#349) Signed-off-by: 1222-takeshi --- .../behavior_velocity_planner/intersection.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index 1725a4d019..bfcaeb8201 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -10,6 +10,8 @@ intersection_velocity: 2.778 # 2.778m/s = 10.0km/h intersection_max_accel: 0.5 # m/ss detection_area_margin: 0.5 # [m] + detection_area_right_margin: 0.5 # [m] + detection_area_left_margin: 0.5 # [m] detection_area_length: 200.0 # [m] min_predicted_path_confidence: 0.05 collision_start_margin_time: 5.0 # [s] From 907d485dc909200448f7a42ea584ad7a7d60b824 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 9 Jun 2022 19:10:21 +0900 Subject: [PATCH 506/851] fix(planning_launch): remove unused parameter in occlusion_spot.param.yaml (#350) Signed-off-by: Fumiya Watanabe --- .../behavior_velocity_planner/occlusion_spot.param.yaml | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml index be846f70c4..0b93ea5308 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml @@ -3,9 +3,8 @@ occlusion_spot: detection_method: "occupancy_grid" # [-] candidate is "occupancy_grid" or "predicted_object" pass_judge: "smooth_velocity" # [-] candidate is "smooth_velocity" or "current_velocity" - filter_occupancy_grid: true # [-] whether to filter occupancy grid by morphologyEx or not - use_moving_object_ray_cast: true # [-] whether to reflect moving object ray shadow grid map use_object_info: true # [-] whether to reflect object info to occupancy grid map or not + use_moving_object_ray_cast: true # [-] whether to reflect moving object ray shadow grid map use_partition_lanelet: true # [-] whether to use partition lanelet map data pedestrian_vel: 1.5 # [m/s] assume pedestrian is dashing from occlusion at this velocity pedestrian_radius: 0.3 # [m] assume pedestrian width(0.2m) + margin(0.1m) From 8b1c8715d9c93e8818e6275c5385918aa07dfa17 Mon Sep 17 00:00:00 2001 From: k-obitsu <56008637+k-obitsu@users.noreply.github.com> Date: Fri, 10 Jun 2022 08:27:04 +0900 Subject: [PATCH 507/851] fix(stop_line): add ros_parameter (#347) * fix(stop_line): add ros_parameter Signed-off-by: k-obitsu --- .../behavior_velocity_planner/stop_line.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml index 6d723c510c..936bfc76cc 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml @@ -4,5 +4,6 @@ stop_margin: 0.0 stop_check_dist: 2.0 stop_duration_sec: 1.0 + use_initialization_stop_line_state: true debug: show_stopline_collision_check: false # [-] whether to show stopline collision From 2d4911655fae2368bf031c06d47cc36b3342c488 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Fri, 10 Jun 2022 16:51:11 +0900 Subject: [PATCH 508/851] feat!(simulator_launch): replace ogm with simulation ogm sensor (#344) feat!(simulator_launch): replace ogm with simulation ogm sensor Signed-off-by: tanaka3 --- simulator_launch/launch/simulator.launch.xml | 21 ++++++++++---------- 1 file changed, 10 insertions(+), 11 deletions(-) diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index f66519d58f..5ebe48cd9c 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -17,6 +17,16 @@ + + + + + + + + + + @@ -56,17 +66,6 @@
    - - - - - - - - - - - From 52c653e571fc1041133f25aa0dd734ccc7b563c7 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Sat, 11 Jun 2022 19:38:15 +0900 Subject: [PATCH 509/851] feat(obstacle_cruise_planner): update obstacle cruise planner parameter (#348) * update obstacle cruise planner parameter Signed-off-by: yutaka * change default to obstacle stop planner Signed-off-by: yutaka --- .../obstacle_cruise_planner.param.yaml | 20 +------------------ 1 file changed, 1 insertion(+), 19 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index 32af994e49..708c23f5ba 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -10,13 +10,13 @@ min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] safe_distance_margin : 6.0 # This is also used as a stop margin [m] - min_strong_accel: -3.0 # obstacle stop requiring deceleration less than this value will be ignored [m/ss] lpf_gain_for_accel: 0.2 # gain of low pass filter for ego acceleration [-] nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index min_behavior_stop_margin: 3.0 # [m] + obstacle_velocity_threshold_from_cruise_to_stop : 3.0 # stop planning is executed to the obstacle whose velocity is less than this value [m/s] cruise_obstacle_type: unknown: true @@ -76,10 +76,7 @@ min_cruise_target_vel: 0.0 # minimum target velocity during slow down [m/s] - obstacle_velocity_threshold_from_cruise_to_stop : 3.0 # stop planning is executed to the obstacle whose velocity is less than this value [m/s] - optimization_based_planner: - limit_min_accel: -3.0 resampling_s_interval: 2.0 dense_resampling_time_interval: 0.1 sparse_resampling_time_interval: 1.0 @@ -89,23 +86,8 @@ velocity_margin: 0.1 #[m/s] # Parameters for safe distance - safe_distance_margin: 5.0 t_dangerous: 0.5 - # Parameters for collision detection - collision_time_threshold: 10.0 - object_zero_velocity_threshold: 3.0 #[m/s] - object_low_velocity_threshold: 3.0 #[m/s] - external_velocity_limit: 20.0 #[m/s] - delta_yaw_threshold_of_object_and_ego: 90.0 # [deg] - delta_yaw_threshold_of_nearest_index: 60.0 # [deg] - collision_duration_threshold_of_object_and_ego: 1.0 # [s] - - # Switch for each functions - enable_adaptive_cruise: true - use_object_acceleration: false - use_hd_map: true - # For initial Motion replan_vel_deviation: 5.0 # 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) From ddfe5c0a730e67eed41dfaca855a2c456f887f01 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 Jun 2022 08:19:10 +0900 Subject: [PATCH 510/851] ci(pre-commit): autoupdate (#337) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit updates: - [github.com/pre-commit/pre-commit-hooks: v4.2.0 → v4.3.0](https://github.com/pre-commit/pre-commit-hooks/compare/v4.2.0...v4.3.0) - [github.com/scop/pre-commit-shfmt: v3.5.0-1 → v3.5.1-1](https://github.com/scop/pre-commit-shfmt/compare/v3.5.0-1...v3.5.1-1) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .pre-commit-config.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index ede7eb7ef7..0052ad3d93 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -4,7 +4,7 @@ ci: repos: - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.2.0 + rev: v4.3.0 hooks: - id: check-json - id: check-merge-conflict @@ -46,7 +46,7 @@ repos: - id: shellcheck - repo: https://github.com/scop/pre-commit-shfmt - rev: v3.5.0-1 + rev: v3.5.1-1 hooks: - id: shfmt args: [-w, -s, -i=4] From 636c394f530b18104c7878368008dd627937e2e1 Mon Sep 17 00:00:00 2001 From: TakumiKozaka-T4 <70260442+TakumiKozaka-T4@users.noreply.github.com> Date: Wed, 15 Jun 2022 15:40:16 +0900 Subject: [PATCH 511/851] feat(autoware_api_launch): add calibration status launcher (#332) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * chore: sync awf-latest (#322) style: fix flake8 C417 (#321) Signed-off-by: Kenji Miyake Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * chore: sync awf-latest (#325) * chore: sync files (#311) Signed-off-by: GitHub Co-authored-by: kenji-miyake * feat: disable namespace `lane_start_bound` (#314) * feat: disable lane_bound * fix: lane_start_bound * feat: add center_line_arrows to disable * ci: add sync-awf.yaml (#318) * ci: add sync-awf.yaml Signed-off-by: Kenji Miyake * rename Signed-off-by: Kenji Miyake * refactor(vehicle_cmd_gate): add namespace (#316) Signed-off-by: Takamasa Horibe * style: fix flake8 C417 (#321) Signed-off-by: Kenji Miyake * chore(behavior_velocity): update latest params (#320) * chore(behavior_velocity): update latest params Signed-off-by: tanaka3 * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * ci(pre-commit): autoupdate (#324) updates: - [github.com/tier4/pre-commit-hooks-ros: v0.7.0 → v0.7.1](https://github.com/tier4/pre-commit-hooks-ros/compare/v0.7.0...v0.7.1) - [github.com/scop/pre-commit-shfmt: v3.4.3-1 → v3.5.0-1](https://github.com/scop/pre-commit-shfmt/compare/v3.4.3-1...v3.5.0-1) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * feat(autoware_api_launch): add rtc controller (#305) * add rtc controller Signed-off-by: tkhmy * change line Signed-off-by: tkhmy * change back to alphabetical order Signed-off-by: tkhmy Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Co-authored-by: kenji-miyake Co-authored-by: Hiroki OTA Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Takamasa Horibe Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kah Hooi Tan <41041286+tkhmy@users.noreply.github.com> * add calibration status launcher to external_api_adaptor Signed-off-by: TakumiKozaka-T4 * pull awf-latest Signed-off-by: TakumiKozaka-T4 * chore: sync awf-latest (#334) * chore: sync files (#327) Signed-off-by: GitHub Co-authored-by: kenji-miyake * refactor: virtual wall rviz config (#326) Signed-off-by: Takamasa Horibe * feat(rviz_plugin): adaptive scaling for display size (#329) Signed-off-by: Takamasa Horibe * fix: support context dict key for humble (#328) * fix: support context dict key for humble Signed-off-by: wep21 * add todo comment Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * fix: modify type of global parameter (#333) Signed-off-by: wep21 * chore: sync files (#335) Signed-off-by: GitHub Co-authored-by: kenji-miyake * feat: use multithread for traffic light container as default (#336) Signed-off-by: tomoya.kimura * fix(localization_launch): fix input topic name (#338) * feat(behavior_velocity): add run out module (#339) * feat(behavior_velocity): add parameter yaml for behavior_velocity_planner Signed-off-by: Tomohito Ando * feat(behavior_velocity): add run out module Signed-off-by: Tomohito Ando * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Co-authored-by: kenji-miyake Co-authored-by: Takamasa Horibe Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Tomoya Kimura Co-authored-by: Yamato Ando Co-authored-by: Tomohito ANDO Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * fix(mission_planner): disable lane_start_bound in Rviz (#341) Signed-off-by: h-ohta * pull the latest tier4/universe Signed-off-by: TakumiKozaka-T4 * pull awf-latest Signed-off-by: TakumiKozaka-T4 * fixed unnecessary change. Signed-off-by: TakumiKozaka-T4 Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: kenji-miyake Co-authored-by: Hiroki OTA Co-authored-by: Takamasa Horibe Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kah Hooi Tan <41041286+tkhmy@users.noreply.github.com> Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: Tomoya Kimura Co-authored-by: Yamato Ando Co-authored-by: Tomohito ANDO --- .../launch/include/external_api_adaptor.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_api_launch/launch/include/external_api_adaptor.launch.py b/autoware_api_launch/launch/include/external_api_adaptor.launch.py index fb840f4edd..a97ef50049 100644 --- a/autoware_api_launch/launch/include/external_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/external_api_adaptor.launch.py @@ -29,6 +29,7 @@ def _create_api_node(node_name, class_name, **kwargs): def generate_launch_description(): components = [ + _create_api_node("calibration_status", "CalibrationStatus"), _create_api_node("cpu_usage", "CpuUsage"), _create_api_node("diagnostics", "Diagnostics"), _create_api_node("door", "Door"), From 5ffcbb747398f22d3834cf548158c3c7c1ca7df8 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 16 Jun 2022 18:00:18 +0900 Subject: [PATCH 512/851] feat: add maneuver to rviz visualization (#353) Signed-off-by: yutaka --- autoware_launch/rviz/autoware.rviz | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 4d59ac9b1d..e1cfc00d80 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -846,6 +846,18 @@ Visualization Manager: Alpha: 0.999 Color: 255; 255; 255 Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Maneuver + Namespaces: + maneuver: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/object_recognition/prediction/maneuver + Value: true Enabled: true Name: Prediction - Class: rviz_common/Group From 8224df2013b66ffa4be0b94f480bf2d992c33366 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 21 Jun 2022 02:42:45 +0900 Subject: [PATCH 513/851] ci(pre-commit): autoupdate (#354) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit updates: - [github.com/pre-commit/mirrors-prettier: v2.6.2 → v2.7.1](https://github.com/pre-commit/mirrors-prettier/compare/v2.6.2...v2.7.1) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .pre-commit-config.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 0052ad3d93..47e3b6eec1 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -24,7 +24,7 @@ repos: args: [-c, .markdownlint.yaml, --fix] - repo: https://github.com/pre-commit/mirrors-prettier - rev: v2.6.2 + rev: v2.7.1 hooks: - id: prettier From 12a959ebc01e331b04cda8c9f1984777d2b1b8b8 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Tue, 21 Jun 2022 18:38:56 +0900 Subject: [PATCH 514/851] fix(autoware_launch): fix autoware.rviz for separating walkway module (#356) Signed-off-by: Fumiya Watanabe --- autoware_launch/rviz/autoware.rviz | 24 ++++++++++++++++++++++++ 1 file changed, 24 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index e1cfc00d80..420b2dff49 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1032,6 +1032,18 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/crosswalk Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (Walkway) + 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/virtual_wall/walkway + Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true Name: VirtualWall (DetectionArea) @@ -1169,6 +1181,18 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Walkway + 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/walkway + Value: false - Class: rviz_default_plugins/MarkerArray Enabled: false Name: Intersection From 003edde5d6b6a9aa97be4afaafcb9bacc6c68854 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Thu, 23 Jun 2022 11:49:10 +0900 Subject: [PATCH 515/851] feat: change data association param (#359) Signed-off-by: Yukihiro Saito --- .../multi_object_tracker/data_association_matrix.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml index 6e7ac3e9ef..b741e1d3d6 100644 --- a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml +++ b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml @@ -61,4 +61,4 @@ 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE - 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] #PEDESTRIAN + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.0001] #PEDESTRIAN From 918855a50b1bcc054644c64b7d595c7443eb1709 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Thu, 23 Jun 2022 12:15:59 +0900 Subject: [PATCH 516/851] feat: sync awf perception launch (#358) * feat: sync awf perception launch Signed-off-by: Yukihiro Saito * bug fix Signed-off-by: Yukihiro Saito --- .../data_association_matrix.param.yaml | 34 ++++----- ...ra_lidar_fusion_based_detection.launch.xml | 69 +++++++++++-------- .../lidar_based_detection.launch.xml | 30 +++++--- 3 files changed, 77 insertions(+), 56 deletions(-) diff --git a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml index b741e1d3d6..5c98f73bcd 100644 --- a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml +++ b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml @@ -1,19 +1,19 @@ /**: ros__parameters: can_assign_matrix: - #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE PEDESTRIAN - [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN - 1, 1, 1, 1, 1, 0, 0, 0, #CAR - 1, 1, 1, 1, 1, 0, 0, 0, #TRUCK - 1, 1, 1, 1, 1, 0, 0, 0, #BUS - 1, 1, 1, 1, 1, 0, 0, 0, #TRAILER + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN <-Measurement + [1, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN <-Tracker + 0, 1, 1, 1, 1, 0, 0, 0, #CAR + 0, 1, 1, 1, 1, 0, 0, 0, #TRUCK + 0, 1, 1, 1, 1, 0, 0, 0, #BUS + 0, 1, 1, 1, 1, 0, 0, 0, #TRAILER 0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE 0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE 0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN max_dist_matrix: #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN - [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN + [4.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS @@ -28,7 +28,7 @@ 19.75, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #TRUCK 32.40, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #BUS 32.40, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #TRAILER - 3.00, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #MOTORBIKE + 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #MOTORBIKE 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #BICYCLE 2.00, 10000.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00] #PEDESTRIAN min_area_matrix: @@ -52,13 +52,13 @@ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN - min_iou_matrix: + min_iou_matrix: # If value is negative, it will be ignored. #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN - [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN - 0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR - 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK - 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS - 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER - 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE - 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE - 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.0001] #PEDESTRIAN + [0.0001, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN + 0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.0001] #PEDESTRIAN 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 af20464cdf..9c52441fb9 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 @@ -1,6 +1,6 @@ - + @@ -38,13 +38,14 @@ - - - - + + + + + @@ -54,6 +55,16 @@ + + + + + + + + + + @@ -84,13 +95,13 @@ - - + + - - + + @@ -103,8 +114,7 @@ - - + @@ -112,7 +122,7 @@ - + @@ -129,8 +139,8 @@ - - + + @@ -147,20 +157,19 @@ - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + 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 e32dcac20b..5287fb4ab6 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 @@ -8,10 +8,10 @@ - - - - + + + + @@ -25,13 +25,21 @@ + + + + + + + + + - - + @@ -57,8 +65,8 @@ - - + + @@ -78,9 +86,13 @@ + + + + + - From 3c7562aef494f062a0b0438ee55a51c6ecf0db46 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Thu, 23 Jun 2022 16:13:23 +0900 Subject: [PATCH 517/851] feat: sync awf perception launch (#360) Signed-off-by: Yukihiro Saito --- .../pointcloud_map_filter.param.yaml | 5 + ...ra_lidar_fusion_based_detection.launch.xml | 14 +- .../lidar_based_detection.launch.xml | 14 +- .../detection/pointcloud_map_filter.launch.py | 168 ++++++++++++++++++ 4 files changed, 191 insertions(+), 10 deletions(-) create mode 100644 perception_launch/config/object_recognition/detection/pointcloud_map_filter.param.yaml create mode 100644 perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py diff --git a/perception_launch/config/object_recognition/detection/pointcloud_map_filter.param.yaml b/perception_launch/config/object_recognition/detection/pointcloud_map_filter.param.yaml new file mode 100644 index 0000000000..a07a9416c2 --- /dev/null +++ b/perception_launch/config/object_recognition/detection/pointcloud_map_filter.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + use_down_sample_filter: False + down_sample_voxel_size: 0.1 + distance_threshold: 0.5 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 9c52441fb9..2fee81fc1b 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 @@ -21,6 +21,8 @@ + + - - - - - + + + + + + + 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 5287fb4ab6..360dcc2587 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 @@ -4,14 +4,18 @@ + + - - - - - + + + + + + + diff --git a/perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py b/perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py new file mode 100644 index 0000000000..afcf9021c0 --- /dev/null +++ b/perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py @@ -0,0 +1,168 @@ +# Copyright 2022 TIER IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +import os + +from ament_index_python.packages import get_package_share_directory +import launch +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes +from launch_ros.descriptions import ComposableNode +import yaml + + +class PointcloudMapFilterPipeline: + def __init__(self, context): + pointcloud_map_filter_param_path = os.path.join( + get_package_share_directory("perception_launch"), + "config/object_recognition/detection/pointcloud_map_filter.param.yaml", + ) + with open(pointcloud_map_filter_param_path, "r") as f: + self.pointcloud_map_filter_param = yaml.safe_load(f)["/**"]["ros__parameters"] + self.use_down_sample_filter = self.pointcloud_map_filter_param["use_down_sample_filter"] + self.voxel_size = self.pointcloud_map_filter_param["down_sample_voxel_size"] + self.distance_threshold = self.pointcloud_map_filter_param["distance_threshold"] + + def create_pipeline(self): + if self.use_down_sample_filter: + return self.create_down_sample_pipeline() + else: + return self.create_normal_pipeline() + + def create_normal_pipeline(self): + components = [] + components.append( + ComposableNode( + package="compare_map_segmentation", + plugin="compare_map_segmentation::VoxelBasedCompareMapFilterComponent", + name="voxel_based_compare_map_filter", + remappings=[ + ("input", LaunchConfiguration("input_topic")), + ("map", "/map/pointcloud_map"), + ("output", LaunchConfiguration("output_topic")), + ], + parameters=[ + { + "distance_threshold": self.distance_threshold, + } + ], + extra_arguments=[ + {"use_intra_process_comms": False}, + ], + ) + ) + return components + + def create_down_sample_pipeline(self): + components = [] + down_sample_topic = ( + "/perception/obstacle_segmentation/pointcloud_map_filtered/downsampled/pointcloud" + ) + components.append( + ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", + name="voxel_grid_downsample_filter", + remappings=[ + ("input", LaunchConfiguration("input_topic")), + ("output", down_sample_topic), + ], + parameters=[ + { + "voxel_size_x": self.voxel_size, + "voxel_size_y": self.voxel_size, + "voxel_size_z": self.voxel_size, + } + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ), + ) + components.append( + ComposableNode( + package="compare_map_segmentation", + plugin="compare_map_segmentation::VoxelBasedCompareMapFilterComponent", + name="voxel_based_compare_map_filter", + remappings=[ + ("input", down_sample_topic), + ("map", "/map/pointcloud_map"), + ("output", LaunchConfiguration("output_topic")), + ], + parameters=[ + { + "distance_threshold": self.distance_threshold, + } + ], + extra_arguments=[ + {"use_intra_process_comms": False}, + ], + ) + ) + return components + + +def launch_setup(context, *args, **kwargs): + pipeline = PointcloudMapFilterPipeline(context) + components = [] + components.extend(pipeline.create_pipeline()) + individual_container = ComposableNodeContainer( + name=LaunchConfiguration("container_name"), + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=components, + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), + output="screen", + ) + pointcloud_container_loader = LoadComposableNodes( + composable_node_descriptions=components, + target_container=LaunchConfiguration("container_name"), + condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), + ) + return [individual_container, pointcloud_container_loader] + + +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("input_topic", "") + add_launch_arg("output_topic", "") + add_launch_arg("use_multithread", "False") + add_launch_arg("use_intra_process", "True") + add_launch_arg("use_pointcloud_container", "False") + add_launch_arg("container_name", "pointcloud_map_filter_pipeline_container") + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + return launch.LaunchDescription( + launch_arguments + + [set_container_executable, set_container_mt_executable] + + [OpaqueFunction(function=launch_setup)] + ) From 7c1d37973c80e4ae2019c5805f302cdd2b38fbe1 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Thu, 23 Jun 2022 19:49:27 +0900 Subject: [PATCH 518/851] feat: sync tracking param (#363) Signed-off-by: Yukihiro Saito --- .../data_association_matrix.param.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml index 5c98f73bcd..1f52e525c4 100644 --- a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml +++ b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml @@ -24,10 +24,10 @@ max_area_matrix: #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN [10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, #UNKNOWN - 12.10, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #CAR - 19.75, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #TRUCK - 32.40, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #BUS - 32.40, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #TRAILER + 12.10, 12.10, 19.75, 40.00, 40.00, 10000.00, 10000.00, 10000.00, #CAR + 19.75, 12.10, 19.75, 40.00, 40.00, 10000.00, 10000.00, 10000.00, #TRUCK + 40.00, 12.10, 19.75, 40.00, 40.00, 10000.00, 10000.00, 10000.00, #BUS + 40.00, 12.10, 19.75, 40.00, 40.00, 10000.00, 10000.00, 10000.00, #TRAILER 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #MOTORBIKE 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #BICYCLE 2.00, 10000.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00] #PEDESTRIAN From 5e0580f40656c03727eb162ad08857a967b1e20a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 24 Jun 2022 11:32:58 +0900 Subject: [PATCH 519/851] feat(planning_launch): update obstacle cruise param (#364) * feat(planning_launch): update obstacle cruise param Signed-off-by: Takayuki Murooka * Delete utils.param.yaml --- .../obstacle_cruise_planner/obstacle_cruise_planner.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index 708c23f5ba..d3d21ff83c 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -76,6 +76,8 @@ min_cruise_target_vel: 0.0 # minimum target velocity during slow down [m/s] + lpf_cruise_gain: 0.2 + optimization_based_planner: resampling_s_interval: 2.0 dense_resampling_time_interval: 0.1 From c7a698cb7324ec14ec8ce446d13f57fc25262e21 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 28 Jun 2022 09:21:54 +0900 Subject: [PATCH 520/851] chore: sync files (#368) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index db998fae00..746d6bd3ba 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -22,7 +22,7 @@ jobs: build-depends-repos: build_depends.repos steps: - name: Cancel previous runs - uses: styfle/cancel-workflow-action@0.9.1 + uses: styfle/cancel-workflow-action@0.10.0 - name: Check out repository uses: actions/checkout@v3 From 1de14ae82e375d8d8805b55dfb1080f7cef24a42 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Tue, 28 Jun 2022 15:37:50 +0900 Subject: [PATCH 521/851] feat(distortion_corrector): use gyroscope for correcting LiDAR distortion (#365) * resolve conflict Signed-off-by: kminoda * update readme Signed-off-by: kminoda --- README.md | 4 ++-- .../launch/twist_estimator/twist_estimator.launch.xml | 10 +++------- 2 files changed, 5 insertions(+), 9 deletions(-) diff --git a/README.md b/README.md index b1ff82b201..b22428a818 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ # autoware_launcher -## Getting Started +## Getting started ### Using real vehicle @@ -14,7 +14,7 @@ ros2 launch autoware_launch autoware.launch.xml map_path:=/path/to/map_folder ve ros2 launch autoware_launch planning_simulator.launch.xml map_path:=/path/to/map_folder vehicle_model:=[vehicle_name] sensor_model:=[sensor_name] ``` -## Directory Structure +## Directory structure - [autoware_launch](./autoware_launch) - [control_launch](./control_launch) diff --git a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml index fd7854a7e4..155521a0ed 100644 --- a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml +++ b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml @@ -1,12 +1,8 @@ - - - - - - - + + + From 962e18dd270adbf1a2969281d47c2fa3bda916b4 Mon Sep 17 00:00:00 2001 From: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Date: Thu, 30 Jun 2022 10:31:24 +0900 Subject: [PATCH 522/851] fix(intersection_module): remove decel parameter (#370) Signed-off-by: 1222-takeshi --- .../behavior_velocity_planner/intersection.param.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index bfcaeb8201..828298fc17 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -2,7 +2,6 @@ ros__parameters: intersection: state_transit_margin_time: 0.5 - decel_velocity: 8.33 # 8.33m/s = 30.0km/h stop_line_margin: 3.0 stuck_vehicle_detect_dist: 3.0 # this should be the length between cars when they are stopped. The actual stuck vehicle detection length will be this value + vehicle_length. stuck_vehicle_ignore_dist: 7.0 # obstacle stop max distance(5.0m) + stuck vehicle size / 2 (0.0m-) From 01653764043de1e2a1067f5745ead07de4ce1a4b Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Thu, 30 Jun 2022 13:26:29 +0900 Subject: [PATCH 523/851] refactor(freespace_planner): parameterize margin (#372) Signed-off-by: Shumpei Wakabayashi --- .../parking/freespace_planner/freespace_planner.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml b/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml index 72648a9dfd..5bc8a56613 100644 --- a/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml +++ b/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml @@ -8,6 +8,7 @@ th_stopped_time_sec: 1.0 th_stopped_velocity_mps: 0.01 th_course_out_distance_m: 1.0 + vehicle_footprint_margin_m: 1.0 replan_when_obstacle_found: true replan_when_course_out: true From db7d16c6409f4b46e39f8aaebe0f6a1646cc7044 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Thu, 30 Jun 2022 14:04:03 +0900 Subject: [PATCH 524/851] refactor(freespace_planner): parameterize margin (#374) Signed-off-by: Shumpei Wakabayashi --- .../parking/freespace_planner/freespace_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml b/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml index 5bc8a56613..d6152c4f56 100644 --- a/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml +++ b/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml @@ -8,7 +8,7 @@ th_stopped_time_sec: 1.0 th_stopped_velocity_mps: 0.01 th_course_out_distance_m: 1.0 - vehicle_footprint_margin_m: 1.0 + vehicle_shape_margin_m: 1.0 replan_when_obstacle_found: true replan_when_course_out: true From c98a8584005e5e9d3f250055bd87803918003d94 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 30 Jun 2022 14:30:30 +0900 Subject: [PATCH 525/851] feat(planning_launch): update obstacle_cruise param (#369) Signed-off-by: Takayuki Murooka --- .../obstacle_cruise_planner.param.yaml | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index d3d21ff83c..9b50aba0e2 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -6,7 +6,7 @@ is_showing_debug_info: true # longitudinal info - idling_time: 4.0 # idling time to detect front vehicle starting deceleration [s] + idling_time: 1.5 # idling time to detect front vehicle starting deceleration [s] min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] safe_distance_margin : 6.0 # This is also used as a stop margin [m] @@ -17,6 +17,7 @@ nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index min_behavior_stop_margin: 3.0 # [m] obstacle_velocity_threshold_from_cruise_to_stop : 3.0 # stop planning is executed to the obstacle whose velocity is less than this value [m/s] + obstacle_velocity_threshold_from_stop_to_cruise : 3.5 # stop planning is executed to the obstacle whose velocity is less than this value [m/s] cruise_obstacle_type: unknown: true @@ -39,7 +40,7 @@ pedestrian: true obstacle_filtering: - rough_detection_area_expand_width : 5.0 # rough lateral margin for rough detection area expansion [m] + rough_detection_area_expand_width : 3.0 # rough lateral margin for rough detection area expansion [m] detection_area_expand_width : 0.0 # lateral margin for precise detection area expansion decimate_trajectory_step_length : 2.0 # longitudinal step length to calculate trajectory polygon for collision checking @@ -48,6 +49,7 @@ crossing_obstacle_traj_angle_threshold : 1.22 # [rad] = 70 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop collision_time_margin : 8.0 # time threshold of collision between obstacle adn ego for cruise or stop [s] + outside_rough_detection_area_expand_width : 0.5 # rough lateral margin for rough detection area expansion for obstacles outside the trajectory [m] ego_obstacle_overlap_time_threshold : 1.0 # time threshold to decide cut-in obstacle for cruise or stop [s] max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego @@ -65,14 +67,14 @@ # use_predicted_obstacle_pose: false # PID gains to keep safe distance with the front vehicle - kp: 0.6 + kp: 2.5 ki: 0.0 - kd: 0.5 + kd: 2.3 min_accel_during_cruise: -2.0 # minimum acceleration during cruise to slow down [m/ss] - output_ratio_during_accel: 2.5 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-] - vel_to_acc_weight: 8.0 # target acceleration is calculated by (target_velocity - current_velocity) * vel_to_acc_weight [-] + output_ratio_during_accel: 0.6 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-] + vel_to_acc_weight: 3.0 # target acceleration is calculated by (target_velocity - current_velocity) * vel_to_acc_weight [-] min_cruise_target_vel: 0.0 # minimum target velocity during slow down [m/s] From c5ce8e152c266fe23b6c7c39f81312a976cce855 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 4 Jul 2022 10:25:34 +0900 Subject: [PATCH 526/851] feat(trajectory_follower): integrate latlon controller (#366) * feat(trajectory_follower): integrate latlon controller Signed-off-by: kosuke55 * update from review comment Signed-off-by: Takamasa Horibe * Set steer converged params false Signed-off-by: kosuke55 Co-authored-by: Takamasa Horibe --- .../latlon_muxer.param.yaml | 3 - .../longitudinal_controller.param.yaml | 2 +- .../mpc_follower.param.yaml | 6 +- control_launch/launch/control.launch.py | 118 +++--------------- 4 files changed, 19 insertions(+), 110 deletions(-) delete mode 100644 control_launch/config/trajectory_follower/latlon_muxer.param.yaml diff --git a/control_launch/config/trajectory_follower/latlon_muxer.param.yaml b/control_launch/config/trajectory_follower/latlon_muxer.param.yaml deleted file mode 100644 index 371bb99787..0000000000 --- a/control_launch/config/trajectory_follower/latlon_muxer.param.yaml +++ /dev/null @@ -1,3 +0,0 @@ -/**: - ros__parameters: - timeout_thr_sec: 0.5 # [s] Time limit after which input messages are discarded. diff --git a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml index d6b987f542..704c291ee2 100644 --- a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml +++ b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml @@ -1,11 +1,11 @@ /**: ros__parameters: - longitudinal_ctrl_period: 0.03 delay_compensation_time: 0.17 enable_smooth_stop: true enable_overshoot_emergency: true enable_slope_compensation: true + enable_keep_stopped_until_steer_convergence: false # state transition drive_state_stop_dist: 0.5 diff --git a/control_launch/config/trajectory_follower/mpc_follower.param.yaml b/control_launch/config/trajectory_follower/mpc_follower.param.yaml index f8a129af4d..e7e3598504 100644 --- a/control_launch/config/trajectory_follower/mpc_follower.param.yaml +++ b/control_launch/config/trajectory_follower/mpc_follower.param.yaml @@ -1,8 +1,6 @@ /**: ros__parameters: - # -- system -- - ctrl_period: 0.03 # control period [s] traj_resample_dist: 0.1 # path resampling interval [m] use_steer_prediction: false # flag for using steer prediction (do not use steer measurement) admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value @@ -57,6 +55,10 @@ # stop state: steering command is kept in the previous value in the stop state. stop_state_entry_ego_speed: 0.001 stop_state_entry_target_speed: 0.001 + converged_steer_rad: 0.1 + keep_steer_control_until_converged: false + new_traj_duration_time: 1.0 + new_traj_end_dist: 0.3 # vehicle parameters vehicle: diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index a4671689d1..811ac38599 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -19,12 +19,10 @@ from launch.actions import OpaqueFunction from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition -from launch.conditions import LaunchConfigurationEquals from launch.conditions import UnlessCondition from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes from launch_ros.actions import PushRosNamespace from launch_ros.descriptions import ComposableNode from launch_ros.substitutions import FindPackageShare @@ -38,10 +36,6 @@ def launch_setup(context, *args, **kwargs): lon_controller_param_path = LaunchConfiguration("lon_controller_param_path").perform(context) with open(lon_controller_param_path, "r") as f: lon_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] - latlon_muxer_param_path = LaunchConfiguration("latlon_muxer_param_path").perform(context) - with open(latlon_muxer_param_path, "r") as f: - latlon_muxer_param = yaml.safe_load(f)["/**"]["ros__parameters"] - vehicle_cmd_gate_param_path = LaunchConfiguration("vehicle_cmd_gate_param_path").perform( context ) @@ -53,73 +47,28 @@ def launch_setup(context, *args, **kwargs): with open(lane_departure_checker_param_path, "r") as f: lane_departure_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] - # lateral controller - mpc_follower_component = ComposableNode( + controller_component = ComposableNode( package="trajectory_follower_nodes", - plugin="autoware::motion::control::trajectory_follower_nodes::LateralController", - name="lateral_controller_node_exe", + plugin="autoware::motion::control::trajectory_follower_nodes::Controller", + name="controller_node_exe", namespace="trajectory_follower", remappings=[ ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), ("~/input/current_odometry", "/localization/kinematic_state"), ("~/input/current_steering", "/vehicle/status/steering_status"), - ("~/output/control_cmd", "lateral/control_cmd"), ("~/output/predicted_trajectory", "lateral/predicted_trajectory"), - ("~/output/diagnostic", "lateral/diagnostic"), - ], - parameters=[ - lat_controller_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - pure_pursuit_component = ComposableNode( - package="pure_pursuit", - plugin="pure_pursuit::PurePursuitNode", - name="pure_pursuit_node_exe", - namespace="trajectory_follower", - remappings=[ - ("input/reference_trajectory", "/planning/scenario_planning/trajectory"), - ("input/current_odometry", "/localization/kinematic_state"), - ("output/control_raw", "lateral/control_cmd"), - ], - parameters=[ - lat_controller_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # longitudinal controller - lon_controller_component = ComposableNode( - package="trajectory_follower_nodes", - plugin="autoware::motion::control::trajectory_follower_nodes::LongitudinalController", - name="longitudinal_controller_node_exe", - namespace="trajectory_follower", - remappings=[ - ("~/input/current_trajectory", "/planning/scenario_planning/trajectory"), - ("~/input/current_odometry", "/localization/kinematic_state"), - ("~/output/control_cmd", "longitudinal/control_cmd"), + ("~/output/lateral_diagnostic", "lateral/diagnostic"), ("~/output/slope_angle", "longitudinal/slope_angle"), - ("~/output/diagnostic", "longitudinal/diagnostic"), - ], - parameters=[ - lon_controller_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # latlon muxer - latlon_muxer_component = ComposableNode( - package="trajectory_follower_nodes", - plugin="autoware::motion::control::trajectory_follower_nodes::LatLonMuxer", - name="latlon_muxer_node_exe", - namespace="trajectory_follower", - remappings=[ - ("~/input/lateral/control_cmd", "lateral/control_cmd"), - ("~/input/longitudinal/control_cmd", "longitudinal/control_cmd"), + ("~/output/longitudinal_diagnostic", "longitudinal/diagnostic"), ("~/output/control_cmd", "control_cmd"), ], parameters=[ - latlon_muxer_param, + { + "ctrl_period": 0.03, + "lateral_controller_mode": LaunchConfiguration("lateral_controller_mode"), + }, + lon_controller_param, + lat_controller_param, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) @@ -226,56 +175,25 @@ def launch_setup(context, *args, **kwargs): ], ) - # set container to run all required components in the same process - mpc_follower_container = ComposableNodeContainer( + container = ComposableNodeContainer( name="control_container", namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ - lon_controller_component, - latlon_muxer_component, + controller_component, lane_departure_component, shift_decider_component, vehicle_cmd_gate_component, ], - condition=LaunchConfigurationEquals("lateral_controller_mode", "mpc_follower"), - ) - pure_pursuit_container = ComposableNodeContainer( - name="control_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[ - lon_controller_component, - latlon_muxer_component, - shift_decider_component, - vehicle_cmd_gate_component, - ], - condition=LaunchConfigurationEquals("lateral_controller_mode", "pure_pursuit"), - ) - - # lateral controller is separated since it may be another controller (e.g. pure pursuit) - mpc_follower_loader = LoadComposableNodes( - composable_node_descriptions=[mpc_follower_component], - target_container=mpc_follower_container, - condition=LaunchConfigurationEquals("lateral_controller_mode", "mpc_follower"), - ) - pure_pursuit_loader = LoadComposableNodes( - composable_node_descriptions=[pure_pursuit_component], - target_container=pure_pursuit_container, - condition=LaunchConfigurationEquals("lateral_controller_mode", "pure_pursuit"), ) group = GroupAction( [ PushRosNamespace("control"), - mpc_follower_container, - pure_pursuit_container, + container, external_cmd_selector_loader, external_cmd_converter_loader, - mpc_follower_loader, - pure_pursuit_loader, ] ) @@ -314,14 +232,6 @@ def add_launch_arg(name: str, default_value=None, description=None): ], "path to the parameter file of longitudinal controller", ) - add_launch_arg( - "latlon_muxer_param_path", - [ - FindPackageShare("control_launch"), - "/config/trajectory_follower/latlon_muxer.param.yaml", - ], - "path to the parameter file of latlon muxer", - ) add_launch_arg( "vehicle_cmd_gate_param_path", [ From 83403b2987e693bb4d30fd9fac125bfe7fec3149 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 4 Jul 2022 14:44:51 +0900 Subject: [PATCH 527/851] feat(obstacle_avoidance_planner): add options for plan_from_ego (#371) Signed-off-by: kosuke55 --- .../obstacle_avoidance_planner.param.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 667d2644f1..87493df635 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -58,7 +58,8 @@ option: steer_limit_constraint: true fix_points_around_ego: true - # plan_from_ego: false + plan_from_ego: false + max_plan_from_ego_length: 10.0 visualize_sampling_num: 1 enable_manual_warm_start: true enable_warm_start: true # false From 570e640b21b6b1916695d0b522df8be7ff2cb37c Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 4 Jul 2022 15:11:02 +0900 Subject: [PATCH 528/851] feat(crosswalk_traffic_light_estimator): launch traffic light estimator (#376) * feat(traffic_light_estimator): launch traffic light estimator Signed-off-by: satoshi-ota * fix(perception_launch): add flag to launch traffic_light_estimator Signed-off-by: satoshi-ota * fix(perception_launch): rename crosswalk_traffic_light_estimator Signed-off-by: satoshi-ota --- .../traffic_light.launch.xml | 2 + .../traffic_light_node_container.launch.py | 45 ++++++++++++++++++- perception_launch/package.xml | 1 + 3 files changed, 47 insertions(+), 1 deletion(-) 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 64252eaf7c..ae79eae500 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -17,6 +17,7 @@ + @@ -37,6 +38,7 @@ + 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 3f16c9a043..8827dfbb98 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 @@ -67,6 +67,7 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("input_h", "224") add_launch_arg("input_w", "224") + add_launch_arg("use_crosswalk_traffic_light_estimator", "True") add_launch_arg("use_intra_process", "False") add_launch_arg("use_multithread", "False") @@ -101,7 +102,7 @@ def create_parameter_dict(*args): remappings=[ ("~/input/image", LaunchConfiguration("input/image")), ("~/input/rois", "rois"), - ("~/output/traffic_signals", "traffic_signals"), + ("~/output/traffic_signals", "classified/traffic_signals"), ], extra_arguments=[ {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} @@ -130,6 +131,46 @@ def create_parameter_dict(*args): output="both", ) + estimator_loader = LoadComposableNodes( + composable_node_descriptions=[ + ComposableNode( + package="crosswalk_traffic_light_estimator", + plugin="traffic_light::CrosswalkTrafficLightEstimatorNode", + name="crosswalk_traffic_light_estimator", + remappings=[ + ("~/input/vector_map", "/map/vector_map"), + ("~/input/route", "/planning/mission_planning/route"), + ("~/input/classified/traffic_signals", "classified/traffic_signals"), + ("~/output/traffic_signals", "traffic_signals"), + ], + extra_arguments=[{"use_intra_process_comms": False}], + ), + ], + target_container=container, + condition=IfCondition(LaunchConfiguration("use_crosswalk_traffic_light_estimator")), + ) + + relay_loader = LoadComposableNodes( + composable_node_descriptions=[ + ComposableNode( + package="topic_tools", + plugin="topic_tools::RelayNode", + name="classified_signals_relay", + namespace="", + parameters=[ + {"input_topic": "classified/traffic_signals"}, + {"output_topic": "traffic_signals"}, + {"type": "autoware_auto_perception_msgs/msg/TrafficSignalArray"}, + ], + extra_arguments=[ + {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} + ], + ) + ], + target_container=container, + condition=UnlessCondition(LaunchConfiguration("use_crosswalk_traffic_light_estimator")), + ) + decompressor_loader = LoadComposableNodes( composable_node_descriptions=[ ComposableNode( @@ -205,5 +246,7 @@ def create_parameter_dict(*args): container, decompressor_loader, fine_detector_loader, + estimator_loader, + relay_loader, ] ) diff --git a/perception_launch/package.xml b/perception_launch/package.xml index 4c5673c04f..a49fa414d0 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -11,6 +11,7 @@ ament_cmake_auto compare_map_segmentation + crosswalk_traffic_light_estimator euclidean_cluster ground_segmentation image_projection_based_fusion From ca3e2c7cc18c1073190fe3751747c0994e9e92dd Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 5 Jul 2022 10:25:53 +0900 Subject: [PATCH 529/851] ci(pre-commit): autoupdate (#383) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit updates: - [github.com/psf/black: 22.3.0 → 22.6.0](https://github.com/psf/black/compare/22.3.0...22.6.0) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .pre-commit-config.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 47e3b6eec1..9f08293e43 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -57,7 +57,7 @@ repos: - id: isort - repo: https://github.com/psf/black - rev: 22.3.0 + rev: 22.6.0 hooks: - id: black args: [--line-length=100] From 4065264d30364b71c97d95c9dc4d37b8a35c5b75 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 5 Jul 2022 12:08:21 +0900 Subject: [PATCH 530/851] feat(control_launch): add disable-emergency option in velocity_controller (#377) Signed-off-by: Takamasa Horibe --- .../trajectory_follower/longitudinal_controller.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml index 704c291ee2..8ef60c0ef6 100644 --- a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml +++ b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml @@ -4,6 +4,7 @@ enable_smooth_stop: true enable_overshoot_emergency: true + enable_large_tracking_error_emergency: true enable_slope_compensation: true enable_keep_stopped_until_steer_convergence: false From d66eb3c93e254d1825a660f93a4e80aca9bf0992 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Tue, 5 Jul 2022 16:41:12 +0900 Subject: [PATCH 531/851] feat(ekf_localizer): allow multi sensor input (#380) Signed-off-by: kminoda --- .../pose_twist_fusion_filter.launch.xml | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) 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 be07542d16..016838dd0d 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 @@ -3,7 +3,7 @@ - + @@ -16,8 +16,6 @@ - - From 40c3f19956392036185fa30ee050e5e09adac5c8 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Wed, 6 Jul 2022 01:32:17 +0900 Subject: [PATCH 532/851] feat: add line_width property to object display (#378) Signed-off-by: tomoya.kimura --- autoware_launch/rviz/autoware.rviz | 3 +++ 1 file changed, 3 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 420b2dff49..abd25da9b3 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -727,6 +727,7 @@ Visualization Manager: Display Twist: true Display UUID: true Display Velocity: true + Line Width: 0.03 Enabled: true MOTORCYCLE: Alpha: 0.999 @@ -774,6 +775,7 @@ Visualization Manager: Display Twist: true Display UUID: true Display Velocity: true + Line Width: 0.03 Enabled: true MOTORCYCLE: Alpha: 0.999 @@ -821,6 +823,7 @@ Visualization Manager: Display Twist: false Display UUID: true Display Velocity: true + Line Width: 0.03 Enabled: true MOTORCYCLE: Alpha: 0.999 From a683916b809af40ec055c1e96353daaca282abc2 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Wed, 6 Jul 2022 01:44:08 +0900 Subject: [PATCH 533/851] feat: add option to use validator node in detection module (#385) * feat: add option to use validator node in detection module Signed-off-by: tomoya.kimura * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../camera_lidar_fusion_based_detection.launch.xml | 7 +++++-- .../detection/lidar_based_detection.launch.xml | 8 ++++++-- 2 files changed, 11 insertions(+), 4 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 2fee81fc1b..d812352f92 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 @@ -23,6 +23,7 @@ + + + - + 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 360dcc2587..5f43169c77 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 @@ -6,6 +6,8 @@ + + @@ -79,7 +81,7 @@ - + @@ -88,8 +90,10 @@ + + - + From 602c46f4abd353a8a42fc219aee6b182f9ec6588 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 6 Jul 2022 16:17:37 +0900 Subject: [PATCH 534/851] feat(planning_launch): update params for new crosswalk module (#375) * feat(planning_launch): add new crosswalk params Signed-off-by: satoshi-ota * chore(planning_launch): add paramter description Signed-off-by: satoshi-ota --- .../crosswalk.param.yaml | 51 +++++++++++++++---- 1 file changed, 40 insertions(+), 11 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml index 92e8ba6801..4ea3229d46 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml @@ -1,14 +1,43 @@ /**: ros__parameters: crosswalk: - crosswalk: - stop_line_distance: 1.5 # make stop line away from crosswalk when no explicit stop line exists - stop_margin: 1.0 - slow_margin: 2.0 - slow_velocity: 2.76 # 2.76 m/s = 10.0 kmph - stop_predicted_object_prediction_time_margin: 3.0 - - walkway: - stop_line_distance: 1.5 # make stop line away from walkway when no explicit stop line exists - stop_margin: 1.0 - stop_duration_sec: 1.0 + show_processing_time: false # [-] whether to show processing time + + # param for stop position + stop_line_distance: 3.5 # [m] make stop line away from crosswalk when no explicit stop line exists + stop_line_margin: 10.0 # [m] if objects cross X meters behind the stop line, the stop position is determined according to the object position (stop_margin meters before the object) + stop_margin: 2.0 # [m] the vehicle decelerates to be able to stop in front of object with margin + stop_position_threshold: 1.0 # [m] threshold for check whether the vehicle stop in front of crosswalk + + # param for ego velocity + slow_velocity: 2.78 # [m/s] target vehicle velocity when module receive slow down command from FOA (2.78 m/s = 10.0 kmph) + max_slow_down_jerk: -1.5 # [m/sss] minimum jerk deceleration for safe brake + max_slow_down_accel: -2.5 # [m/ss] minimum accel deceleration for safe brake + no_relax_velocity: 2.78 # [m/s] if the current velocity is less than X m/s, ego always stops at the stop position(not relax deceleration constraints 2.78 m/s = 10 kmph) + + # param for stuck vehicle + stuck_vehicle_velocity: 1.0 # [m/s] maximum velocity threshold whether the vehicle is stuck + max_lateral_offset: 2.0 # [m] maximum lateral offset for stuck vehicle position should be looked + stuck_vehicle_attention_range: 10.0 # [m] the detection area is defined as X meters behind the crosswalk + + # param for pass judge logic + ego_pass_first_margin: 6.0 # [s] time margin for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) + ego_pass_later_margin: 10.0 # [s] time margin for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) + stop_object_velocity_threshold: 0.28 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.28 m/s = 1.0 kmph) + min_object_velocity: 1.39 # [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV. 1.39 m/s = 5.0 kmph) + max_yield_timeout: 3.0 # [s] if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first. + + # param for input data + tl_state_timeout: 3.0 # [s] timeout threshold for traffic light signal + + # param for target area & object + crosswalk_attention_range: 1.0 # [m] the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk + target_object: + unknown: true # [-] whether to look and stop by UNKNOWN objects + bicycle: true # [-] whether to look and stop by BICYCLE objects + motorcycle: true # [-] whether to look and stop by MOTORCYCLE objects (tmp: currently it is difficult for perception modules to detect bicycles and motorcycles separately.) + pedestrian: true # [-] whether to look and stop by PEDESTRIAN objects + + walkway: + stop_duration_sec: 1.0 # [s] stop time at stop position + stop_line_distance: 3.5 # [m] make stop line away from crosswalk when no explicit stop line exists From fb4503f3ec0cf4e9f42bc1a9cd539830ae843cb9 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Wed, 6 Jul 2022 17:30:35 +0900 Subject: [PATCH 535/851] feat(autoware_launch): add perception mode (#388) * feat(autoware_launch): add perception mode Signed-off-by: yutaka * Update autoware_launch/launch/autoware.launch.xml Co-authored-by: Yukihiro Saito Co-authored-by: Yukihiro Saito --- autoware_launch/launch/autoware.launch.xml | 3 ++- autoware_launch/launch/logging_simulator.launch.xml | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 2b7bf1861f..bb44f49523 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -7,6 +7,7 @@ + @@ -70,7 +71,7 @@ - + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 1cc48dbc85..41c05eec1e 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -19,6 +19,7 @@ + @@ -86,7 +87,7 @@ - + From 64fde69d7dbeecf3622916a872b1b4adbc48b0cf Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 6 Jul 2022 18:55:16 +0900 Subject: [PATCH 536/851] chore(planning_launch): fix some parameters (#382) * chore(planning_launch): disable debug message Signed-off-by: Takayuki Murooka * ignore outside unknown obstacle Signed-off-by: Takayuki Murooka --- .../obstacle_cruise_planner.param.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index 9b50aba0e2..3b067b65dd 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -3,7 +3,7 @@ common: planning_algorithm: "pid_base" # currently supported algorithm is "pid_base" - is_showing_debug_info: true + is_showing_debug_info: false # longitudinal info idling_time: 1.5 # idling time to detect front vehicle starting deceleration [s] @@ -54,7 +54,7 @@ max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego ignored_outside_obstacle_type: - unknown: false + unknown: true car: false truck: false bus: false From d6e0b9842e8b7038b9a3b8c46865bd1971d5f845 Mon Sep 17 00:00:00 2001 From: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Date: Thu, 7 Jul 2022 01:54:35 +0900 Subject: [PATCH 537/851] feat(perception_launcher): add radar fusion launcher (#387) * feat(perception_launcher): add radar fusion launcher Signed-off-by: scepter914 * fix typo Signed-off-by: scepter914 * Update perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml Co-authored-by: Yukihiro Saito * fix lidar_object arg Signed-off-by: scepter914 * devide camera_lidar_radar_fusion and lidar_radar_fusion Signed-off-by: scepter914 * fix typo Signed-off-by: scepter914 * fix namespace for debug Signed-off-by: scepter914 * Update perception_launch/launch/object_recognition/detection/detection.launch.xml Co-authored-by: Yukihiro Saito * Update autoware_launch/launch/autoware.launch.xml Co-authored-by: Yukihiro Saito * fix typo Signed-off-by: scepter914 * fix typo Signed-off-by: scepter914 * fix typo Signed-off-by: scepter914 * Update perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml Co-authored-by: Yukihiro Saito * Update perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml Co-authored-by: Yukihiro Saito * Update perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml Co-authored-by: Yukihiro Saito * revert rviz launcher in logging_simulator.launch.xml Signed-off-by: scepter914 * Update autoware_launch/launch/logging_simulator.launch.xml Co-authored-by: Yukihiro Saito * Update perception_launch/launch/perception.launch.xml Co-authored-by: Yukihiro Saito * add namespace to lidar based objects Signed-off-by: scepter914 * add radar based detection in detection.launch Signed-off-by: scepter914 Co-authored-by: Yukihiro Saito --- autoware_launch/launch/autoware.launch.xml | 3 +- .../launch/logging_simulator.launch.xml | 3 +- ...ra_lidar_fusion_based_detection.launch.xml | 3 +- ...ar_radar_fusion_based_detection.launch.xml | 68 +++++++++++++++++++ .../detection/detection.launch.xml | 55 +++++++++++++-- .../lidar_based_detection.launch.xml | 3 +- .../lidar_radar_based_detection.launch.xml | 32 +++++++++ .../radar_based_detection.launch.xml | 12 ++++ .../launch/perception.launch.xml | 4 +- 9 files changed, 171 insertions(+), 12 deletions(-) create mode 100644 perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml create mode 100644 perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml create mode 100644 perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index bb44f49523..39cc926f2f 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -7,7 +7,7 @@ - + @@ -70,7 +70,6 @@ - diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 41c05eec1e..355b08d130 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -19,7 +19,7 @@ - + @@ -86,7 +86,6 @@ - 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 d812352f92..0007744203 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 @@ -2,6 +2,7 @@ + @@ -177,6 +178,6 @@ - + diff --git a/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml new file mode 100644 index 0000000000..d2a59a4a45 --- /dev/null +++ b/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -0,0 +1,68 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception_launch/launch/object_recognition/detection/detection.launch.xml b/perception_launch/launch/object_recognition/detection/detection.launch.xml index 0fc359043d..e30297a495 100644 --- a/perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -1,10 +1,14 @@ + + + - - + + + @@ -22,7 +26,34 @@ - + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -49,6 +80,16 @@ + + + + + + + + + + @@ -57,7 +98,11 @@ - - + + + + + + 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 5f43169c77..2bf826f762 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 @@ -2,6 +2,7 @@ + @@ -100,7 +101,7 @@ - + diff --git a/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml new file mode 100644 index 0000000000..a0eef1825b --- /dev/null +++ b/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml new file mode 100644 index 0000000000..6fb6184d6a --- /dev/null +++ b/perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 1b5b2d750a..9c90589fc1 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -3,7 +3,8 @@ - + + @@ -67,6 +68,7 @@ + From c28993f58549d65ac214561fc682520a618c9a1c Mon Sep 17 00:00:00 2001 From: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Date: Thu, 7 Jul 2022 10:06:22 +0900 Subject: [PATCH 538/851] feat(perception_launch): Insert detected object filter (#381) * Insert object filter Signed-off-by: Shunsuke Miura * Change package name, add param yaml Signed-off-by: Shunsuke Miura * Add args for param.yaml Signed-off-by: Shunsuke Miura --- .../detection/object_lanelet_filter.param.yaml | 11 +++++++++++ .../detection/object_position_filter.param.yaml | 16 ++++++++++++++++ ...amera_lidar_fusion_based_detection.launch.xml | 11 ++++++++++- .../detection/lidar_based_detection.launch.xml | 10 ++++++++++ 4 files changed, 47 insertions(+), 1 deletion(-) create mode 100644 perception_launch/config/object_recognition/detection/object_lanelet_filter.param.yaml create mode 100644 perception_launch/config/object_recognition/detection/object_position_filter.param.yaml diff --git a/perception_launch/config/object_recognition/detection/object_lanelet_filter.param.yaml b/perception_launch/config/object_recognition/detection/object_lanelet_filter.param.yaml new file mode 100644 index 0000000000..dfdee95642 --- /dev/null +++ b/perception_launch/config/object_recognition/detection/object_lanelet_filter.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + filter_target_label: + UNKNOWN : true + CAR : false + TRUCK : false + BUS : false + TRAILER : false + MOTORCYCLE : false + BICYCLE : false + PEDESTRIAN : false diff --git a/perception_launch/config/object_recognition/detection/object_position_filter.param.yaml b/perception_launch/config/object_recognition/detection/object_position_filter.param.yaml new file mode 100644 index 0000000000..70afd9d31b --- /dev/null +++ b/perception_launch/config/object_recognition/detection/object_position_filter.param.yaml @@ -0,0 +1,16 @@ +/**: + ros__parameters: + filter_target_label: + UNKNOWN : true + CAR : false + TRUCK : false + BUS : false + TRAILER : false + MOTORCYCLE : false + BICYCLE : false + PEDESTRIAN : false + + upper_bound_x: 100.0 + lower_bound_x: 0.0 + upper_bound_y: 10.0 + lower_bound_y: -10.0 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 0007744203..052449d050 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 @@ -178,6 +178,15 @@ - + + + + + + + + + + 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 2bf826f762..aee2084c79 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 @@ -101,7 +101,17 @@ + + + + + + + + + + From 47aa6f6d03a9675b2fd7a61375477a27aa599bb6 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Thu, 7 Jul 2022 10:13:36 +0900 Subject: [PATCH 539/851] chore(behavior_velocity): update config for run_out (#390) Signed-off-by: Tomohito Ando --- .../behavior_velocity_planner/run_out.param.yaml | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml index 8818ed0199..527c00ccf3 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml @@ -12,13 +12,9 @@ detection_span: 1.0 # [m] calculate collision with this span to reduce calculation time min_vel_ego_kmph: 3.6 # [km/h] min velocity to calculate time to collision - # rectangle detection area for Points method - # this will be replaced with more appropriate detection area - detection_area_size: - dist_ahead: 50.0 # [m] ahead distance from ego position - dist_behind: 5.0 # [m] behind distance from ego position - dist_right: 7.0 # [m] right distance from ego position - dist_left: 7.0 # [m] left distance from ego position + detection_area: + margin_behind: 0.5 # [m] ahead margin for detection area length + margin_ahead: 1.0 # [m] behind margin for detection area length # parameter to create abstracted dynamic obstacles dynamic_obstacle: From 324848f642c5dee4f531a91b157d442686c3f93e Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 7 Jul 2022 12:59:45 +0900 Subject: [PATCH 540/851] feat(control_launch): add param for cmd gate transition filter (#386) Signed-off-by: Takamasa Horibe --- .../vehicle_cmd_gate.param.yaml | 17 ++++++++++++----- 1 file changed, 12 insertions(+), 5 deletions(-) diff --git a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml b/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml index 0ad4631c6d..4876699351 100644 --- a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml +++ b/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml @@ -6,8 +6,15 @@ stop_hold_acceleration: -1.5 emergency_acceleration: -2.4 stopped_state_entry_duration_time: 0.1 - vel_lim: 25.0 - lon_acc_lim: 5.0 - lon_jerk_lim: 5.0 - lat_acc_lim: 5.0 - lat_jerk_lim: 5.0 + nominal: + vel_lim: 25.0 + lon_acc_lim: 5.0 + lon_jerk_lim: 5.0 + lat_acc_lim: 5.0 + lat_jerk_lim: 5.0 + on_transition: + vel_lim: 50.0 + lon_acc_lim: 1.0 + lon_jerk_lim: 0.5 + lat_acc_lim: 1.2 + lat_jerk_lim: 0.75 From 9299af468f714ecd22edb0f64315753314bc92f9 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 7 Jul 2022 14:17:07 +0900 Subject: [PATCH 541/851] fix(planning_launch): replace lost count to lost time for avoidance (#384) Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_planner/avoidance/avoidance.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index d691228589..2e04b3e159 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -32,7 +32,7 @@ nominal_lateral_jerk: 0.2 # [m/s3] max_lateral_jerk: 1.0 # [m/s3] - object_hold_max_count: 20 + object_last_seen_threshold: 2.0 # For prevention of large acceleration while avoidance min_avoidance_speed_for_acc_prevention: 3.0 # [m/s] From b1777f091595536e0624558269d51f26849a8ea3 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 7 Jul 2022 17:10:17 +0900 Subject: [PATCH 542/851] feat(obstacle_cruise_planner): add stop obstacle hold time (#389) Signed-off-by: yutaka --- .../obstacle_cruise_planner/obstacle_cruise_planner.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index 3b067b65dd..c23ce72f3b 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -53,6 +53,8 @@ ego_obstacle_overlap_time_threshold : 1.0 # time threshold to decide cut-in obstacle for cruise or stop [s] max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego + stop_obstacle_hold_time_threshold : 1.0 # maximum time for holding closest stop obstacle + ignored_outside_obstacle_type: unknown: true car: false From 11b30f1973299ea682ce5f2baf7fe9ccfced6d2e Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Thu, 7 Jul 2022 17:13:24 +0900 Subject: [PATCH 543/851] feat: change iou param of multi object tracking (#391) Signed-off-by: Yukihiro Saito --- .../multi_object_tracker/data_association_matrix.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml index 1f52e525c4..6fb495c258 100644 --- a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml +++ b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml @@ -55,7 +55,7 @@ min_iou_matrix: # If value is negative, it will be ignored. #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN [0.0001, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN - 0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR + 0.1, 0.1, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER From 1a27bb45ccdb3a65fcf92efc4ca25af4bd204a84 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 7 Jul 2022 21:11:30 +0900 Subject: [PATCH 544/851] fix(behavior_path_planner): revert road shoulder margin to zero (#357) Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_planner/avoidance/avoidance.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index 2e04b3e159..1b820b2c2b 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -24,7 +24,7 @@ min_nominal_avoidance_speed: 7.0 # [m/s] min_sharp_avoidance_speed: 1.0 # [m/s] - road_shoulder_safety_margin: 0.5 # [m] + road_shoulder_safety_margin: 0.0 # [m] max_right_shift_length: 5.0 max_left_shift_length: 5.0 From d3ab37403b5f7f008550d91d102970ff472c9fe0 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 8 Jul 2022 00:03:07 +0900 Subject: [PATCH 545/851] feat: add operation mode transition manager (#392) * feat: add-operation-mode-transition-manager Signed-off-by: Takamasa Horibe * fix precommit Signed-off-by: Takamasa Horibe * add param Signed-off-by: Takamasa Horibe --- ...eration_mode_transition_manager.param.yaml | 18 ++++++++ control_launch/launch/control.launch.py | 41 +++++++++++++++++++ control_launch/launch/control.launch.xml | 2 + 3 files changed, 61 insertions(+) create mode 100644 control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml diff --git a/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml b/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml new file mode 100644 index 0000000000..d42e2392be --- /dev/null +++ b/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml @@ -0,0 +1,18 @@ +/**: + ros__parameters: + frequency_hz: 10.0 + engage_acceptable_limits: + allow_autonomous_in_stopped: true # no check if the velocity is zero, always allowed. + dist_threshold: 1.5 + yaw_threshold: 0.524 + speed_upper_threshold: 10.0 + speed_lower_threshold: -10.0 + acc_threshold: 1.5 + lateral_acc_threshold: 1.0 + lateral_acc_diff_threshold: 0.5 + stable_check: + duration: 0.1 + dist_threshold: 1.5 + speed_upper_threshold: 2.0 + speed_lower_threshold: -2.0 + yaw_threshold: 0.262 diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 811ac38599..f948a547ed 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -47,6 +47,12 @@ def launch_setup(context, *args, **kwargs): with open(lane_departure_checker_param_path, "r") as f: lane_departure_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] + operation_mode_transition_manager_param_path = LaunchConfiguration( + "operation_mode_transition_manager_param_path" + ).perform(context) + with open(operation_mode_transition_manager_param_path, "r") as f: + operation_mode_transition_manager_param = yaml.safe_load(f)["/**"]["ros__parameters"] + controller_component = ComposableNode( package="trajectory_follower_nodes", plugin="autoware::motion::control::trajectory_follower_nodes::Controller", @@ -113,6 +119,7 @@ def launch_setup(context, *args, **kwargs): remappings=[ ("input/emergency_state", "/system/emergency/emergency_state"), ("input/steering", "/vehicle/status/steering_status"), + ("input/operation_mode", "/control/operation_mode"), ("input/auto/control_cmd", "/control/trajectory_follower/control_cmd"), ("input/auto/turn_indicators_cmd", "/planning/turn_indicators_cmd"), ("input/auto/hazard_lights_cmd", "/planning/hazard_lights_cmd"), @@ -134,6 +141,7 @@ def launch_setup(context, *args, **kwargs): ("output/gate_mode", "/control/current_gate_mode"), ("output/engage", "/api/autoware/get/engage"), ("output/external_emergency", "/api/autoware/get/emergency"), + ("output/operation_mode", "/control/vehicle_cmd_gate/operation_mode"), ("~/service/engage", "/api/autoware/set/engage"), ("~/service/external_emergency", "/api/autoware/set/emergency"), # TODO(Takagi, Isamu): deprecated @@ -152,6 +160,30 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + # operation mode transition manager + operation_mode_transition_manager_component = ComposableNode( + package="operation_mode_transition_manager", + plugin="operation_mode_transition_manager::OperationModeTransitionManager", + name="operation_mode_transition_manager", + remappings=[ + # input + ("kinematics", "/localization/kinematic_state"), + ("steering", "/vehicle/status/steering_status"), + ("trajectory", "/planning/scenario_planning/trajectory"), + ("control_cmd", "/control/command/control_cmd"), + ("control_mode_report", "/vehicle/status/control_mode"), + ("gate_operation_mode", "/control/vehicle_cmd_gate/operation_mode"), + ("operation_mode_request", "/system/operation_mode_request"), + # output + ("is_autonomous_available", "/control/is_autonomous_available"), + ("operation_mode", "/control/operation_mode"), + ("control_mode_request", "/control/control_mode_request"), + ], + parameters=[ + operation_mode_transition_manager_param, + ], + ) + # external cmd selector external_cmd_selector_loader = IncludeLaunchDescription( PythonLaunchDescriptionSource( @@ -185,6 +217,7 @@ def launch_setup(context, *args, **kwargs): lane_departure_component, shift_decider_component, vehicle_cmd_gate_component, + operation_mode_transition_manager_component, ], ) @@ -244,6 +277,14 @@ def add_launch_arg(name: str, default_value=None, description=None): "lane_departure_checker_param_path", [FindPackageShare("lane_departure_checker"), "/config/lane_departure_checker.param.yaml"], ) + add_launch_arg( + "operation_mode_transition_manager_param_path", + [ + FindPackageShare("control_launch"), + "/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml", + ], + "path to the parameter file of vehicle_cmd_gate", + ) # vehicle cmd gate add_launch_arg("use_emergency_handling", "false", "use emergency handling") diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index 282d9e52f5..90974363ea 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -5,6 +5,7 @@ + @@ -12,6 +13,7 @@ + From a925b4e4c6d02dc930ffdc20fba4d57e31ab2b64 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 8 Jul 2022 00:42:42 +0900 Subject: [PATCH 546/851] feat(trajectory_follower): add min_prediction_length to mpc (#393) Signed-off-by: kosuke55 --- .../config/trajectory_follower/mpc_follower.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/control_launch/config/trajectory_follower/mpc_follower.param.yaml b/control_launch/config/trajectory_follower/mpc_follower.param.yaml index e7e3598504..8941a4c46d 100644 --- a/control_launch/config/trajectory_follower/mpc_follower.param.yaml +++ b/control_launch/config/trajectory_follower/mpc_follower.param.yaml @@ -38,6 +38,7 @@ mpc_zero_ff_steer_deg: 0.5 # threshold that feed-forward angle becomes zero mpc_acceleration_limit: 2.0 # limit on the vehicle's acceleration mpc_velocity_time_constant: 0.3 # time constant used for velocity smoothing + mpc_min_prediction_length: 5.0 # minimum prediction length # -- vehicle model -- vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics From 2670c6103e7b811447005eb3592185db42832a9a Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Fri, 8 Jul 2022 11:57:54 +0900 Subject: [PATCH 547/851] feat(autoware_launch): add perception mode to sensing launch (#396) --- autoware_launch/launch/autoware.launch.xml | 1 + autoware_launch/launch/logging_simulator.launch.xml | 1 + 2 files changed, 2 insertions(+) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 39cc926f2f..d4975c6464 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -59,6 +59,7 @@ + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 355b08d130..c143f2c51b 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -75,6 +75,7 @@ + From 0cccc812eaa6f7ef46638dba6ad52a7e73edac98 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 8 Jul 2022 18:07:30 +0900 Subject: [PATCH 548/851] feat(localization_error_monitor): add a config file (#395) * feat(localization_error_monitor): add a config file Signed-off-by: kminoda * ci(pre-commit): autofix * debugged Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/localization_error_monitor.param.yaml | 7 +++++++ .../localization_error_monitor.launch.xml | 6 +----- 2 files changed, 8 insertions(+), 5 deletions(-) create mode 100644 localization_launch/config/localization_error_monitor.param.yaml diff --git a/localization_launch/config/localization_error_monitor.param.yaml b/localization_launch/config/localization_error_monitor.param.yaml new file mode 100644 index 0000000000..026daf0532 --- /dev/null +++ b/localization_launch/config/localization_error_monitor.param.yaml @@ -0,0 +1,7 @@ +/**: + ros__parameters: + scale: 3.0 + error_ellipse_size: 1.0 + warn_ellipse_size: 0.8 + error_ellipse_size_lateral_direction: 0.3 + warn_ellipse_size_lateral_direction: 0.2 diff --git a/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml b/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml index d2ea9ced7b..ee6047281d 100644 --- a/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml +++ b/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml @@ -2,10 +2,6 @@ - - - - - + From 82667227708782a0e6436df45e1e33c13dc06cc3 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sat, 9 Jul 2022 02:54:19 +0900 Subject: [PATCH 549/851] feat(behavior_path_planner): update pull_over module (#312) * feat(behavior_path_planner): update pull_over module Signed-off-by: kosuke55 * Add pull over rviz Signed-off-by: kosuke55 * updatea rviz config --- autoware_launch/rviz/autoware.rviz | 57 +++++++++++++++++ .../pull_over/pull_over.param.yaml | 61 ++++++++++++++----- 2 files changed, 102 insertions(+), 16 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index abd25da9b3..249cc72cdc 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1304,6 +1304,43 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/run_out Value: false + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: GoalSearchArea + Namespaces: + collision_polygons: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/debug/parking_area + Value: false + - Alpha: 0.9990000128746033 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz_default_plugins/PoseArray + Color: 255; 25; 0 + Enabled: false + Head Length: 0.10000000149011612 + Head Radius: 0.20000000298023224 + Name: PullOverPathPoseArray + Shaft Length: 0.20000000298023224 + Shaft Radius: 0.05000000074505806 + Shape: Arrow (3D) + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/debug/path_pose_array + Value: false + Enabled: false + Name: PullOver Enabled: false Name: DebugMarker Enabled: true @@ -1521,6 +1558,26 @@ Visualization Manager: Value: true Enabled: true Name: Parking + - Alpha: 1 + 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 + Name: ModifiedGoal + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Axes + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/modified_goal + Value: true Enabled: true Name: ScenarioPlanning Enabled: true diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index 08ab028632..d10d63ae3c 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -1,25 +1,54 @@ /**: ros__parameters: pull_over: + request_length: 100.0 + th_arrived_distance_m: 1.0 + th_stopped_velocity_mps: 0.01 + th_stopped_time_sec: 2.0 # It must be greater than the state_machine's. + pull_over_velocity: 2.0 + pull_over_minimum_velocity: 0.3 + margin_from_boundary: 0.5 + decide_path_distance: 10.0 + min_acc: -0.5 + enable_shift_parking: true + enable_arc_forward_parking: true + enable_arc_backward_parking: false + # goal research + search_priority: "efficient_path" # "efficient_path" or "close_goal" + enable_goal_research: true + forward_goal_search_length: 20.0 + backward_goal_search_length: 20.0 + goal_search_interval: 1.0 + goal_to_obj_margin: 2.0 + # occupancy grid map + collision_check_margin: 0.5 + theta_size: 360 + obstacle_threshold: 60 + # shift path + pull_over_sampling_num: 4 + maximum_lateral_jerk: 2.0 + minimum_lateral_jerk: 0.5 + deceleration_interval: 15.0 + maximum_deceleration: 1.0 + after_pull_over_straight_distance: 5.0 + before_pull_over_straight_distance: 5.0 + # parallel parking path + after_forward_parking_straight_distance: 2.0 + after_backward_parking_straight_distance: 2.0 + forward_parking_velocity: 0.3 + backward_parking_velocity: -0.3 + arc_path_interval: 1.0 + # hazard. Not used now. + hazard_on_threshold_dis: 1.0 + hazard_on_threshold_vel: 0.5 + # check safety with dynamic objects. Not used now. + pull_over_duration: 2.0 + pull_over_prepare_duration: 4.0 min_stop_distance: 5.0 stop_time: 2.0 hysteresis_buffer_distance: 2.0 - pull_over_prepare_duration: 4.0 - pull_over_duration: 2.0 - pull_over_finish_judge_buffer: 3.0 - minimum_pull_over_velocity: 3.0 - prediction_duration: 30.0 - prediction_time_resolution: 0.5 - static_obstacle_velocity_thresh: 1.5 - maximum_deceleration: 1.0 enable_collision_check_at_prepare_phase: false use_predicted_path_outside_lanelet: false use_all_predicted_path: false - enable_blocked_by_obstacle: false - pull_over_search_distance: 30.0 - after_pull_over_straight_distance: 5.0 - before_pull_over_straight_distance: 5.0 - margin_from_boundary: 0.5 - maximum_lateral_jerk: 2.0 - minimum_lateral_jerk: 0.5 - deceleration_interval: 15.0 + # debug + print_debug_info: false From 89acef1fa863eb0ac36a78373a3cd2477a161a4a Mon Sep 17 00:00:00 2001 From: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Date: Mon, 11 Jul 2022 12:08:05 +0900 Subject: [PATCH 550/851] fix(perception_launch): fix vehicle param in perception launch (#402) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * chore: sync awf-latest (#322) style: fix flake8 C417 (#321) Signed-off-by: Kenji Miyake Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * chore: sync awf-latest (#325) * chore: sync files (#311) Signed-off-by: GitHub Co-authored-by: kenji-miyake * feat: disable namespace `lane_start_bound` (#314) * feat: disable lane_bound * fix: lane_start_bound * feat: add center_line_arrows to disable * ci: add sync-awf.yaml (#318) * ci: add sync-awf.yaml Signed-off-by: Kenji Miyake * rename Signed-off-by: Kenji Miyake * refactor(vehicle_cmd_gate): add namespace (#316) Signed-off-by: Takamasa Horibe * style: fix flake8 C417 (#321) Signed-off-by: Kenji Miyake * chore(behavior_velocity): update latest params (#320) * chore(behavior_velocity): update latest params Signed-off-by: tanaka3 * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * ci(pre-commit): autoupdate (#324) updates: - [github.com/tier4/pre-commit-hooks-ros: v0.7.0 → v0.7.1](https://github.com/tier4/pre-commit-hooks-ros/compare/v0.7.0...v0.7.1) - [github.com/scop/pre-commit-shfmt: v3.4.3-1 → v3.5.0-1](https://github.com/scop/pre-commit-shfmt/compare/v3.4.3-1...v3.5.0-1) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * feat(autoware_api_launch): add rtc controller (#305) * add rtc controller Signed-off-by: tkhmy * change line Signed-off-by: tkhmy * change back to alphabetical order Signed-off-by: tkhmy Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Co-authored-by: kenji-miyake Co-authored-by: Hiroki OTA Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Takamasa Horibe Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kah Hooi Tan <41041286+tkhmy@users.noreply.github.com> * chore: sync awf-latest (#334) * chore: sync files (#327) Signed-off-by: GitHub Co-authored-by: kenji-miyake * refactor: virtual wall rviz config (#326) Signed-off-by: Takamasa Horibe * feat(rviz_plugin): adaptive scaling for display size (#329) Signed-off-by: Takamasa Horibe * fix: support context dict key for humble (#328) * fix: support context dict key for humble Signed-off-by: wep21 * add todo comment Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * fix: modify type of global parameter (#333) Signed-off-by: wep21 * chore: sync files (#335) Signed-off-by: GitHub Co-authored-by: kenji-miyake * feat: use multithread for traffic light container as default (#336) Signed-off-by: tomoya.kimura * fix(localization_launch): fix input topic name (#338) * feat(behavior_velocity): add run out module (#339) * feat(behavior_velocity): add parameter yaml for behavior_velocity_planner Signed-off-by: Tomohito Ando * feat(behavior_velocity): add run out module Signed-off-by: Tomohito Ando * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Co-authored-by: kenji-miyake Co-authored-by: Takamasa Horibe Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Tomoya Kimura Co-authored-by: Yamato Ando Co-authored-by: Tomohito ANDO Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * fix(mission_planner): disable lane_start_bound in Rviz (#341) Signed-off-by: h-ohta * fix(stop_line): add ros_parameter (#347) * fix(stop_line): add ros_parameter Signed-off-by: k-obitsu * fix(perception_launch): fix vehicle param in perception launch Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: kenji-miyake Co-authored-by: Hiroki OTA Co-authored-by: Takamasa Horibe Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kah Hooi Tan <41041286+tkhmy@users.noreply.github.com> Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: Tomoya Kimura Co-authored-by: Yamato Ando Co-authored-by: Tomohito ANDO Co-authored-by: k-obitsu <56008637+k-obitsu@users.noreply.github.com> --- autoware_launch/rviz/autoware.rviz | 1 + perception_launch/launch/perception.launch.xml | 2 ++ .../behavior_velocity_planner/stop_line.param.yaml | 1 + 3 files changed, 4 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 249cc72cdc..5268291d47 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -903,6 +903,7 @@ Visualization Manager: Name: RouteArea Namespaces: goal_lanelets: true + lane_start_bound: false left_lane_bound: false right_lane_bound: false route_lanelets: true diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 9c90589fc1..eec9eb99c4 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -4,6 +4,7 @@ + @@ -42,6 +43,7 @@ + diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml index 6d723c510c..936bfc76cc 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml @@ -4,5 +4,6 @@ stop_margin: 0.0 stop_check_dist: 2.0 stop_duration_sec: 1.0 + use_initialization_stop_line_state: true debug: show_stopline_collision_check: false # [-] whether to show stopline collision From f9c2b64fc41e69cc6ac46bbc1e12f04eb1b14541 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 11 Jul 2022 12:41:40 +0900 Subject: [PATCH 551/851] fix(planning_launch): update crosswalk config (#401) Signed-off-by: satoshi-ota --- .../behavior_velocity_planner/crosswalk.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml index 4ea3229d46..2cc5260e4e 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml @@ -10,7 +10,7 @@ stop_position_threshold: 1.0 # [m] threshold for check whether the vehicle stop in front of crosswalk # param for ego velocity - slow_velocity: 2.78 # [m/s] target vehicle velocity when module receive slow down command from FOA (2.78 m/s = 10.0 kmph) + min_slow_down_velocity: 2.78 # [m/s] target vehicle velocity when module receive slow down command from FOA (2.78 m/s = 10.0 kmph) max_slow_down_jerk: -1.5 # [m/sss] minimum jerk deceleration for safe brake max_slow_down_accel: -2.5 # [m/ss] minimum accel deceleration for safe brake no_relax_velocity: 2.78 # [m/s] if the current velocity is less than X m/s, ego always stops at the stop position(not relax deceleration constraints 2.78 m/s = 10 kmph) From e611e616ddb827b09ecca22b1de70632361b7075 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Mon, 11 Jul 2022 13:45:59 +0900 Subject: [PATCH 552/851] chore: sync param files (#285) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- ...ate_monitor.planning_simulation.param.yaml | 8 --- ...ror_monitor.planning_simulation.param.yaml | 50 +++++++++++++++++++ 2 files changed, 50 insertions(+), 8 deletions(-) create mode 100644 system_launch/config/system_error_monitor.planning_simulation.param.yaml diff --git a/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml b/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml index a3b20c4c94..b20ffec096 100644 --- a/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml +++ b/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml @@ -23,7 +23,6 @@ topic_configs: names: [ "/map/vector_map", - "/map/pointcloud_map", "/perception/object_recognition/objects", "/initialpose2d", "/planning/mission_planning/route", @@ -43,13 +42,6 @@ type: "autoware_auto_mapping_msgs/msg/HADMapBin" transient_local: True - /map/pointcloud_map: - module: "map" - timeout: 0.0 - warn_rate: 0.0 - type: "sensor_msgs/msg/PointCloud2" - transient_local: True - /perception/object_recognition/objects: module: "perception" timeout: 1.0 diff --git a/system_launch/config/system_error_monitor.planning_simulation.param.yaml b/system_launch/config/system_error_monitor.planning_simulation.param.yaml new file mode 100644 index 0000000000..ce081b75b2 --- /dev/null +++ b/system_launch/config/system_error_monitor.planning_simulation.param.yaml @@ -0,0 +1,50 @@ +# Description: +# name: diag name +# sf_at: diag level where it becomes Safe Fault +# lf_at: diag level where it becomes Latent Fault +# spf_at: diag level where it becomes Single Point Fault +# auto_recovery: Determines whether the system will automatically recover when it recovers from an error. +# +# Note: +# empty-value for sf_at, lf_at and spf_at is "none" +# default values are: +# sf_at: "none" +# lf_at: "warn" +# spf_at: "error" +# auto_recovery: "true" +--- +/**: + ros__parameters: + required_modules: + autonomous_driving: + /autoware/control/autonomous_driving/node_alive_monitoring: default + /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default + /autoware/control/control_command_gate/node_alive_monitoring: default + + /autoware/localization/node_alive_monitoring: default + # /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } + # /autoware/localization/performance_monitoring/localization_accuracy: default + + /autoware/map/node_alive_monitoring: default + + /autoware/perception/node_alive_monitoring: default + + /autoware/planning/node_alive_monitoring: default + /autoware/planning/performance_monitoring/trajectory_validation: default + + /autoware/sensing/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + # /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "error", spf_at: "none" } + + /autoware/vehicle/node_alive_monitoring: default + + external_control: + /autoware/control/control_command_gate/node_alive_monitoring: default + /autoware/control/external_control/external_command_selector/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + + /autoware/vehicle/node_alive_monitoring: default From c31239704da63e038807ff2fc4cb73259b2a621d Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 11 Jul 2022 18:39:55 +0900 Subject: [PATCH 553/851] fix: avoid same name nodes in detection module (#405) Signed-off-by: tomoya.kimura --- .../camera_lidar_fusion_based_detection.launch.xml | 7 +++++++ .../detection/lidar_based_detection.launch.xml | 2 ++ 2 files changed, 9 insertions(+) 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 052449d050..4f134ffaf4 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 @@ -64,11 +64,13 @@ + + @@ -103,11 +105,13 @@ + + @@ -169,16 +173,19 @@ + + + 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 aee2084c79..fa1e46b911 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 @@ -97,11 +97,13 @@ + + From a5578cb0bb00e4d67c22ff62df9c29b3c6582513 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Tue, 12 Jul 2022 12:26:26 +0900 Subject: [PATCH 554/851] feat(system_launch): add group tag around include (#361) Signed-off-by: h-ohta --- system_launch/launch/system.launch.xml | 38 +++++++++++++++----------- 1 file changed, 22 insertions(+), 16 deletions(-) diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index 88aaca8527..6fff875192 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -23,26 +23,32 @@ - - - - - + + + + + + + - - - - - - - - + + + + + + + + + + - - - + + + + + From f0d4a067198306b876b93826b7a7bf5b94d945eb Mon Sep 17 00:00:00 2001 From: TakumiKozaka-T4 <70260442+TakumiKozaka-T4@users.noreply.github.com> Date: Tue, 12 Jul 2022 14:07:37 +0900 Subject: [PATCH 555/851] feat: add launcher for localization api (#404) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * chore: sync awf-latest (#322) style: fix flake8 C417 (#321) Signed-off-by: Kenji Miyake Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * chore: sync awf-latest (#325) * chore: sync files (#311) Signed-off-by: GitHub Co-authored-by: kenji-miyake * feat: disable namespace `lane_start_bound` (#314) * feat: disable lane_bound * fix: lane_start_bound * feat: add center_line_arrows to disable * ci: add sync-awf.yaml (#318) * ci: add sync-awf.yaml Signed-off-by: Kenji Miyake * rename Signed-off-by: Kenji Miyake * refactor(vehicle_cmd_gate): add namespace (#316) Signed-off-by: Takamasa Horibe * style: fix flake8 C417 (#321) Signed-off-by: Kenji Miyake * chore(behavior_velocity): update latest params (#320) * chore(behavior_velocity): update latest params Signed-off-by: tanaka3 * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * ci(pre-commit): autoupdate (#324) updates: - [github.com/tier4/pre-commit-hooks-ros: v0.7.0 → v0.7.1](https://github.com/tier4/pre-commit-hooks-ros/compare/v0.7.0...v0.7.1) - [github.com/scop/pre-commit-shfmt: v3.4.3-1 → v3.5.0-1](https://github.com/scop/pre-commit-shfmt/compare/v3.4.3-1...v3.5.0-1) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * feat(autoware_api_launch): add rtc controller (#305) * add rtc controller Signed-off-by: tkhmy * change line Signed-off-by: tkhmy * change back to alphabetical order Signed-off-by: tkhmy Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Co-authored-by: kenji-miyake Co-authored-by: Hiroki OTA Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Takamasa Horibe Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kah Hooi Tan <41041286+tkhmy@users.noreply.github.com> * chore: sync awf-latest (#334) * chore: sync files (#327) Signed-off-by: GitHub Co-authored-by: kenji-miyake * refactor: virtual wall rviz config (#326) Signed-off-by: Takamasa Horibe * feat(rviz_plugin): adaptive scaling for display size (#329) Signed-off-by: Takamasa Horibe * fix: support context dict key for humble (#328) * fix: support context dict key for humble Signed-off-by: wep21 * add todo comment Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * fix: modify type of global parameter (#333) Signed-off-by: wep21 * chore: sync files (#335) Signed-off-by: GitHub Co-authored-by: kenji-miyake * feat: use multithread for traffic light container as default (#336) Signed-off-by: tomoya.kimura * fix(localization_launch): fix input topic name (#338) * feat(behavior_velocity): add run out module (#339) * feat(behavior_velocity): add parameter yaml for behavior_velocity_planner Signed-off-by: Tomohito Ando * feat(behavior_velocity): add run out module Signed-off-by: Tomohito Ando * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Co-authored-by: kenji-miyake Co-authored-by: Takamasa Horibe Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Tomoya Kimura Co-authored-by: Yamato Ando Co-authored-by: Tomohito ANDO Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * fix(mission_planner): disable lane_start_bound in Rviz (#341) Signed-off-by: h-ohta * fix(stop_line): add ros_parameter (#347) * fix(stop_line): add ros_parameter Signed-off-by: k-obitsu * add localization score relay node Signed-off-by: TakumiKozaka-T4 * pull awf-latest Signed-off-by: TakumiKozaka-T4 Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: kenji-miyake Co-authored-by: Hiroki OTA Co-authored-by: Takamasa Horibe Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kah Hooi Tan <41041286+tkhmy@users.noreply.github.com> Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: Tomoya Kimura Co-authored-by: Yamato Ando Co-authored-by: Tomohito ANDO Co-authored-by: k-obitsu <56008637+k-obitsu@users.noreply.github.com> --- .../launch/include/external_api_adaptor.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_api_launch/launch/include/external_api_adaptor.launch.py b/autoware_api_launch/launch/include/external_api_adaptor.launch.py index a97ef50049..3aafd3d1bb 100644 --- a/autoware_api_launch/launch/include/external_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/external_api_adaptor.launch.py @@ -37,6 +37,7 @@ def generate_launch_description(): _create_api_node("engage", "Engage"), _create_api_node("fail_safe_state", "FailSafeState"), _create_api_node("initial_pose", "InitialPose"), + _create_api_node("localization_score", "LocalizationScore"), _create_api_node("map", "Map"), _create_api_node("operator", "Operator"), _create_api_node("metadata_packages", "MetadataPackages"), From a24d059b1de4491ac1119f3cf16ded3c234af7d3 Mon Sep 17 00:00:00 2001 From: Yusuke Muramatsu Date: Tue, 12 Jul 2022 16:00:11 +0900 Subject: [PATCH 556/851] chore(perception_launch): sync universe/tier4_perception_launch into perception_launch (#408) * chore(perception_launch): sync universe/tier4_perception_launch into perception_launch Signed-off-by: yukke42 * fix: restore unintentionally deleted lines Signed-off-by: yukke42 --- ...ra_lidar_fusion_based_detection.launch.xml | 14 +++---- ...ar_radar_fusion_based_detection.launch.xml | 10 ++--- .../detection/detection.launch.xml | 5 +-- .../lidar_based_detection.launch.xml | 6 +-- .../lidar_radar_based_detection.launch.xml | 10 ++--- .../radar_based_detection.launch.xml | 10 ++--- .../prediction/prediction.launch.xml | 4 +- .../tracking/tracking.launch.xml | 3 +- .../launch/perception.launch.xml | 39 ++++++++++--------- 9 files changed, 48 insertions(+), 53 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 4f134ffaf4..55cf6ab6e4 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 @@ -64,13 +64,13 @@ - + - + @@ -105,13 +105,13 @@ - + - + @@ -173,19 +173,19 @@ - + - + - + diff --git a/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml index d2a59a4a45..d7043c0e36 100644 --- a/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -1,7 +1,7 @@ - + @@ -55,14 +55,14 @@ - + - - - + + + diff --git a/perception_launch/launch/object_recognition/detection/detection.launch.xml b/perception_launch/launch/object_recognition/detection/detection.launch.xml index e30297a495..d74e5659cb 100644 --- a/perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -1,10 +1,9 @@ - - + @@ -102,7 +101,7 @@ - + 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 fa1e46b911..fcca73cf00 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 @@ -9,7 +9,6 @@ - @@ -97,13 +96,13 @@ - + - + @@ -115,5 +114,4 @@ - diff --git a/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml index a0eef1825b..4801466b90 100644 --- a/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml @@ -1,7 +1,7 @@ - + @@ -19,14 +19,14 @@ - + - - - + + + diff --git a/perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml index 6fb6184d6a..21de187f12 100644 --- a/perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml @@ -3,10 +3,10 @@ - - - - - + + + + + diff --git a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml index bd322ff679..fd9d1ba6f3 100644 --- a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml +++ b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml @@ -1,5 +1,4 @@ - @@ -10,7 +9,6 @@ - - + diff --git a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml index 64bcad42fa..aa4aec1537 100644 --- a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml +++ b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml @@ -1,7 +1,6 @@ - - + diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index eec9eb99c4..92fb57061b 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -1,10 +1,9 @@ - - + @@ -25,7 +24,11 @@ - + @@ -37,13 +40,13 @@ - - - - + + + + + - @@ -51,12 +54,12 @@ - - - - - - + + + + + + @@ -94,8 +97,7 @@ - - + @@ -109,15 +111,14 @@ - + - - + From 96958f85da63251dadf13c3b063182de9bcb76f0 Mon Sep 17 00:00:00 2001 From: Yusuke Muramatsu Date: Tue, 12 Jul 2022 16:15:16 +0900 Subject: [PATCH 557/851] fix(perception_launch): pass pointcloud_container params to pointcloud_map_filter in detection module (#409) Signed-off-by: yukke42 --- .../camera_lidar_fusion_based_detection.launch.xml | 4 ++-- ...amera_lidar_radar_fusion_based_detection.launch.xml | 4 ++++ .../object_recognition/detection/detection.launch.xml | 10 ++++++++++ .../detection/lidar_based_detection.launch.xml | 4 ++-- .../detection/lidar_radar_based_detection.launch.xml | 4 ++++ perception_launch/launch/perception.launch.xml | 2 ++ 6 files changed, 24 insertions(+), 4 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 55cf6ab6e4..bc9977d83e 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 @@ -23,7 +23,7 @@ - + @@ -47,7 +47,7 @@ - + diff --git a/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml index d7043c0e36..802694e2ed 100644 --- a/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -4,6 +4,8 @@ + + @@ -48,6 +50,8 @@ + + diff --git a/perception_launch/launch/object_recognition/detection/detection.launch.xml b/perception_launch/launch/object_recognition/detection/detection.launch.xml index d74e5659cb..1196988f07 100644 --- a/perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -6,6 +6,8 @@ + + @@ -51,6 +53,8 @@ + + @@ -77,6 +81,8 @@ + + @@ -86,6 +92,8 @@ + + @@ -95,6 +103,8 @@ + + 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 fcca73cf00..9fa255e823 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 @@ -6,7 +6,7 @@ - + @@ -17,7 +17,7 @@ - + diff --git a/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml index 4801466b90..db1fc26863 100644 --- a/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml @@ -4,6 +4,8 @@ + + @@ -12,6 +14,8 @@ + + diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 92fb57061b..9bfd185631 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -92,6 +92,8 @@ + + From dee0e66f04701b71222aefa7a214642bfd367810 Mon Sep 17 00:00:00 2001 From: Yusuke Muramatsu Date: Thu, 14 Jul 2022 11:37:25 +0900 Subject: [PATCH 558/851] feat(perception_launch): cherry-pick awf/tier4_perception_launch into perception_launch (#412) Signed-off-by: yukke42 --- ...ra_lidar_fusion_based_detection.launch.xml | 203 ++++++++++-------- .../lidar_based_detection.launch.xml | 51 +++-- .../tracking/tracking.launch.xml | 8 +- .../traffic_light.launch.xml | 32 +-- 4 files changed, 174 insertions(+), 120 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 bc9977d83e..a1fd508dcb 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 @@ -54,71 +54,89 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -142,12 +160,20 @@ + + + + + - + + + + @@ -167,33 +193,38 @@ - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + - + 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 9fa255e823..5c9e4e8861 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 @@ -26,20 +26,28 @@ - - - - - - - - - + + + + + + + + + + + + + + + - - - - + + + + + + @@ -64,12 +72,20 @@ + + + + + - + + + + @@ -96,13 +112,14 @@ - + + + - @@ -111,7 +128,7 @@ - + diff --git a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml index aa4aec1537..aac0e32289 100644 --- a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml +++ b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml @@ -1,6 +1,8 @@ - - - + + + + + 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 ae79eae500..6605209150 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -34,20 +34,24 @@ - - - - - - - - - - - - + + + + + + + + + + + + + + - - + + + + From 5c3b978155536da19f32090f0d7190b1587ac499 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Wed, 20 Jul 2022 13:10:51 +0900 Subject: [PATCH 559/851] fix: fix parameter names of motion_velocity_smoother (#418) * fix: fix parameter names of motion_velocity_smoother Signed-off-by: tomoya.kimura * fix Signed-off-by: tomoya.kimura --- .../motion_velocity_smoother.param.yaml | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index adffe53472..016d313e9b 100644 --- a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -32,19 +32,19 @@ # resampling parameters for optimization max_trajectory_length: 200.0 # max trajectory length for resampling [m] min_trajectory_length: 150.0 # min trajectory length for resampling [m] - resample_time: 5.0 # resample total time for dense sampling [s] - dense_dt: 0.1 # resample time interval for dense sampling [s] + resample_time: 5.0 # resample total time for dense sampling [s] + dense_resample_dt: 0.1 # resample time interval for dense sampling [s] dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m] - sparse_dt: 0.5 # resample time interval for sparse sampling [s] + sparse_resample_dt: 0.5 # resample time interval for sparse sampling [s] sparse_min_interval_distance: 4.0 # minimum points-interval length for sparse sampling [m] # resampling parameters for post process post_max_trajectory_length: 300.0 # max trajectory length for resampling [m] post_min_trajectory_length: 30.0 # min trajectory length for resampling [m] - post_resample_time: 10.0 # resample total time for dense sampling [s] - post_dense_dt: 0.1 # resample time interval for dense sampling [s] + post_resample_time: 10.0 # resample total time for dense sampling [s] + post_dense_resample_dt: 0.1 # resample time interval for dense sampling [s] post_dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m] - post_sparse_dt: 0.1 # resample time interval for sparse sampling [s] + post_sparse_resample_dt: 0.1 # resample time interval for sparse sampling [s] post_sparse_min_interval_distance: 1.0 # minimum points-interval length for sparse sampling [m] # system From ad86352c6ca7e18713b70cb5a1ee8718ffba88ab Mon Sep 17 00:00:00 2001 From: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Date: Thu, 21 Jul 2022 12:58:15 +0900 Subject: [PATCH 560/851] feat(intersection_module): add option to change the stopline position (#416) Signed-off-by: 1222-takeshi --- .../behavior_velocity_planner/intersection.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index 828298fc17..2c49ef72e8 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -15,6 +15,7 @@ min_predicted_path_confidence: 0.05 collision_start_margin_time: 5.0 # [s] collision_end_margin_time: 2.0 # [s] + use_stuck_stopline: false # stopline generate before the intersection lanelet when is_stuck merge_from_private_road: stop_duration_sec: 1.0 From 591de7ad7d9e5ea33a874f7bc02fc15f25c2bc53 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Fri, 22 Jul 2022 11:27:01 +0900 Subject: [PATCH 561/851] fix(planning_launch): fix launch file (#417) * fix(planning_launch): fix launch file Signed-off-by: Fumiya Watanabe * fix(planning_launch): fix xml file Signed-off-by: Fumiya Watanabe --- .../behavior_planning.launch.py | 39 ------------------- .../behavior_planning.launch.xml | 8 ---- 2 files changed, 47 deletions(-) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 9313960323..79f8b3d50b 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -17,7 +17,6 @@ from ament_index_python.packages import get_package_share_directory import launch from launch.actions import DeclareLaunchArgument -from launch.actions import ExecuteProcess from launch.actions import IncludeLaunchDescription from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition @@ -134,32 +133,7 @@ def generate_launch_description(): ("~/input/perception", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), ("~/input/scenario", "/planning/scenario_planning/scenario"), - ( - "~/input/external_approval", - "/planning/scenario_planning/lane_driving/behavior_planning/" - "behavior_path_planner/path_change_approval", - ), - ( - "~/input/force_approval", - "/planning/scenario_planning/lane_driving/behavior_planning/" - "behavior_path_planner/path_change_force", - ), ("~/output/path", "path_with_lane_id"), - ( - "~/output/ready", - "/planning/scenario_planning/lane_driving/behavior_planning/" - "behavior_path_planner/ready_module", - ), - ( - "~/output/running", - "/planning/scenario_planning/lane_driving/behavior_planning/" - "behavior_path_planner/running_modules", - ), - ( - "~/output/force_available", - "/planning/scenario_planning/lane_driving/behavior_planning/" - "behavior_path_planner/force_available", - ), ("~/output/turn_indicators_cmd", "/planning/turn_indicators_cmd"), ("~/output/hazard_lights_cmd", "/planning/hazard_lights_cmd"), ], @@ -474,18 +448,5 @@ def generate_launch_description(): set_container_mt_executable, container, load_compare_map, - ExecuteProcess( - cmd=[ - "ros2", - "topic", - "pub", - "/planning/scenario_planning/lane_driving/behavior_planning/" - "behavior_path_planner/path_change_approval", - "tier4_planning_msgs/msg/Approval", - "{approval: true}", - "-r", - "10", - ] - ), ] ) 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 eaf8370d59..9922f6c15d 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,20 +2,12 @@ - - - - - - - From 063a67a81a7641307366835dd5cbdead71dbe194 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 27 Jul 2022 11:26:16 +0900 Subject: [PATCH 562/851] feat(behavior_velocitiy_planner): predict front vehicle deceleration in intersection and temporarily stop (#419) --- .../behavior_velocity_planner/intersection.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index 2c49ef72e8..2f8ebad3ba 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -16,6 +16,8 @@ collision_start_margin_time: 5.0 # [s] collision_end_margin_time: 2.0 # [s] use_stuck_stopline: false # stopline generate before the intersection lanelet when is_stuck + assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of frontcar when frontcar as well as ego are turning + enable_front_car_decel_prediction: false # By default this feature is disabled merge_from_private_road: stop_duration_sec: 1.0 From 114a876e67b4690f7329b10206ad2fc5396ce1eb Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 27 Jul 2022 14:51:24 +0900 Subject: [PATCH 563/851] refactor(trajectory_follower_nodes): use max_steer_angle in common (#420) Signed-off-by: Takayuki Murooka --- .../config/trajectory_follower/mpc_follower.param.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/control_launch/config/trajectory_follower/mpc_follower.param.yaml b/control_launch/config/trajectory_follower/mpc_follower.param.yaml index 8941a4c46d..e8e87e4955 100644 --- a/control_launch/config/trajectory_follower/mpc_follower.param.yaml +++ b/control_launch/config/trajectory_follower/mpc_follower.param.yaml @@ -44,7 +44,6 @@ 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 approximation) [s] - steer_lim_deg: 40.0 # steering angle limit [deg] 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] From 00c214a36a7f5162443f08da7e9ab6cdfc57ad0f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 27 Jul 2022 14:51:53 +0900 Subject: [PATCH 564/851] refactor(obstacle_avoidance_planner): use max_steer_angle in common (#421) * refactor(obstacle_avoidance_planner): use max_steer_angle in common Signed-off-by: Takayuki Murooka * fix runtime error Signed-off-by: Takayuki Murooka --- .../obstacle_avoidance_planner.param.yaml | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 87493df635..f31003da09 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -68,9 +68,7 @@ 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] - kinematics: - max_steer_deg: 40.0 # max steering angle [deg] - + # kinematics: # If this parameter is commented out, the parameter is set as below by default. # The logic could be `optimization_center_offset = vehicle_info.wheel_base * 0.8` # The 0.8 scale is adopted as it performed the best. From b8fec6e269e281c1263ea934a31f2ed36372b2f3 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Mon, 1 Aug 2022 15:00:01 +0900 Subject: [PATCH 565/851] feat(obstacle_cruise_planner): update parameter (#423) * feat(obstacle_cruise_planner: update parameter Signed-off-by: yutaka * empty commit Signed-off-by: yutaka --- .../obstacle_cruise_planner/obstacle_cruise_planner.param.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index c23ce72f3b..a8821c75bb 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -55,6 +55,9 @@ stop_obstacle_hold_time_threshold : 1.0 # maximum time for holding closest stop obstacle + prediction_resampling_time_interval: 0.1 + prediction_resampling_time_horizon: 10.0 + ignored_outside_obstacle_type: unknown: true car: false From d128f28d9b1444fb97cffb48a85f01593d74b791 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 3 Aug 2022 12:29:24 +0900 Subject: [PATCH 566/851] feat(planning_launch): add hold stop margin distance (#424) Signed-off-by: satoshi-ota --- .../behavior_velocity_planner/detection_area.param.yaml | 1 + .../behavior_velocity_planner/stop_line.param.yaml | 4 +--- .../virtual_traffic_light.param.yaml | 1 + .../obstacle_stop_planner/obstacle_stop_planner.param.yaml | 1 + 4 files changed, 4 insertions(+), 3 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml index 9174045bf0..63ca5fc7d9 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml @@ -6,3 +6,4 @@ dead_line_margin: 5.0 use_pass_judge_line: false state_clear_time: 2.0 + hold_stop_margin_distance: 0.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml index 936bfc76cc..0118452b72 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml @@ -2,8 +2,6 @@ ros__parameters: stop_line: stop_margin: 0.0 - stop_check_dist: 2.0 stop_duration_sec: 1.0 + hold_stop_margin_distance: 2.0 use_initialization_stop_line_state: true - debug: - show_stopline_collision_check: false # [-] whether to show stopline collision diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml index 267dde50c7..8879408d40 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml @@ -4,5 +4,6 @@ max_delay_sec: 3.0 near_line_distance: 1.0 dead_line_margin: 1.0 + hold_stop_margin_distance: 0.0 max_yaw_deviation_deg: 90.0 check_timeout_after_stop_line: true diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml index 82a7720334..c708e819b9 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml @@ -6,6 +6,7 @@ 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] + hold_stop_margin_distance: 0.0 # the ego keeps stopping if the ego is in this margin [m] slow_down_planner: # slow down planner parameters From cefe37490c9065e1f4aa3e27114c6b90ac23d180 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 3 Aug 2022 14:25:56 +0900 Subject: [PATCH 567/851] feat(planning_launch): add parameter for hunting prevention (#427) Signed-off-by: satoshi-ota --- .../obstacle_stop_planner/obstacle_stop_planner.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml index c708e819b9..36421cf37a 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml @@ -1,5 +1,7 @@ /**: ros__parameters: + hunting_threshold: 0.5 # even if the obstacle disappears, the stop judgment continues for hunting_threshold [s] + 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] From 3555602d77816a0c14ae2c54cb07f6470321da55 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Thu, 4 Aug 2022 01:20:02 +0900 Subject: [PATCH 568/851] fix(behavior_path_planner): fix turn signal output in a avoidance sequence (#428) Signed-off-by: Shumpei Wakabayashi --- .../behavior_path_planner/lane_change/lane_change.param.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml index 50934a7454..86226a95ce 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -17,4 +17,3 @@ use_predicted_path_outside_lanelet: false use_all_predicted_path: false enable_blocked_by_obstacle: false - lane_change_search_distance: 30.0 From a395e2041fe5442ffcac302204126da3272e010f Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 8 Aug 2022 15:54:15 +0900 Subject: [PATCH 569/851] feat(localization_error_monitor): change subscribing topic type (#430) --- .../localization_error_monitor.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml b/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml index ee6047281d..c895da4917 100644 --- a/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml +++ b/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml @@ -1,7 +1,7 @@ - + From 500997bd97743fa5a9cb94aba20c0e2d8421a9ea Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 15 Aug 2022 09:43:25 +0900 Subject: [PATCH 570/851] fix(behavior_velocity_planner): modify delay_response_time for lexus model (#435) fix(planning_launch): modify delay_response_time for lexus model Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../behavior_velocity_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml index 1332e422cd..5ac74c2015 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml @@ -15,4 +15,4 @@ max_accel: -2.8 max_jerk: -5.0 system_delay: 0.5 - delay_response_time: 1.3 + delay_response_time: 0.5 From 7343f8fa32f871a8412dc22cb8cca55252240509 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Mon, 15 Aug 2022 12:01:36 +0900 Subject: [PATCH 571/851] feat(obstacle_cruise_planner): update parameters (#436) * update parameters Signed-off-by: yutaka * empty Signed-off-by: yutaka --- .../obstacle_cruise_planner.param.yaml | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index a8821c75bb..63c4a5d9a4 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -86,13 +86,11 @@ lpf_cruise_gain: 0.2 optimization_based_planner: - resampling_s_interval: 2.0 - dense_resampling_time_interval: 0.1 - sparse_resampling_time_interval: 1.0 + dense_resampling_time_interval: 0.2 + sparse_resampling_time_interval: 2.0 dense_time_horizon: 5.0 max_time_horizon: 25.0 - max_trajectory_length: 200.0 - velocity_margin: 0.1 #[m/s] + velocity_margin: 0.2 #[m/s] # Parameters for safe distance t_dangerous: 0.5 From 1e2127d904f637d86f9733a1da5ca3387e925ce6 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 17 Aug 2022 10:35:24 +0900 Subject: [PATCH 572/851] feat(rviz): add behavior path debug markers (#441) Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- autoware_launch/rviz/autoware.rviz | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 5268291d47..c69f0ef925 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1305,6 +1305,18 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/run_out Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: BehaviorPath + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/markers + Value: false - Class: rviz_common/Group Displays: - Class: rviz_default_plugins/MarkerArray From a21d3330e707c947b2fa10307547a98ce2dd11fd Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 17 Aug 2022 11:37:34 +0900 Subject: [PATCH 573/851] feat(planning_launch): add nearest search param (#437) * feat(planning_launch): add nearest search param Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../common/nearest_search.param.yaml | 5 +++++ .../behavior_planning/behavior_planning.launch.py | 12 ++++++++++++ .../motion_planning/motion_planning.launch.py | 14 ++++++++++++++ .../scenario_planning/scenario_planning.launch.xml | 2 ++ 4 files changed, 33 insertions(+) create mode 100644 planning_launch/config/scenario_planning/common/nearest_search.param.yaml diff --git a/planning_launch/config/scenario_planning/common/nearest_search.param.yaml b/planning_launch/config/scenario_planning/common/nearest_search.param.yaml new file mode 100644 index 0000000000..eb6709764c --- /dev/null +++ b/planning_launch/config/scenario_planning/common/nearest_search.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + # ego + ego_nearest_dist_threshold: 3.0 # [m] + ego_nearest_yaw_threshold: 1.046 # [rad] = 60 [deg] diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 79f8b3d50b..d0b92a4627 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -31,6 +31,16 @@ def generate_launch_description(): + nearest_search_param_path = os.path.join( + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "common", + "nearest_search.param.yaml", + ) + with open(nearest_search_param_path, "r") as f: + nearest_search_param = yaml.safe_load(f)["/**"]["ros__parameters"] + # behavior path planner side_shift_param_path = os.path.join( get_package_share_directory("planning_launch"), @@ -138,6 +148,7 @@ def generate_launch_description(): ("~/output/hazard_lights_cmd", "/planning/hazard_lights_cmd"), ], parameters=[ + nearest_search_param, side_shift_param, avoidance_param, lane_change_param, @@ -368,6 +379,7 @@ def generate_launch_description(): parameters=[ behavior_velocity_planner_param, common_param, + nearest_search_param, motion_velocity_smoother_param, smoother_type_param, blind_spot_param, diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index 4c341a0670..fc1859eb76 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -40,6 +40,16 @@ def generate_launch_description(): with open(common_param_path, "r") as f: common_param = yaml.safe_load(f)["/**"]["ros__parameters"] + nearest_search_param_path = os.path.join( + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "common", + "nearest_search.param.yaml", + ) + with open(nearest_search_param_path, "r") as f: + nearest_search_param = yaml.safe_load(f)["/**"]["ros__parameters"] + # obstacle avoidance planner obstacle_avoidance_planner_param_path = os.path.join( get_package_share_directory("planning_launch"), @@ -63,6 +73,7 @@ def generate_launch_description(): ("~/output/path", "obstacle_avoidance_planner/trajectory"), ], parameters=[ + nearest_search_param, obstacle_avoidance_planner_param, {"is_showing_debug_info": False}, {"is_stopping_if_outside_drivable_area": True}, @@ -103,6 +114,7 @@ def generate_launch_description(): ("~/input/odometry", "/localization/kinematic_state"), ], parameters=[ + nearest_search_param, surround_obstacle_checker_param, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], @@ -136,6 +148,7 @@ def generate_launch_description(): ], parameters=[ common_param, + nearest_search_param, obstacle_cruise_planner_param, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], @@ -188,6 +201,7 @@ def generate_launch_description(): ], parameters=[ common_param, + nearest_search_param, obstacle_stop_planner_param, obstacle_stop_planner_acc_param, {"enable_slow_down": False}, diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 538607f04a..f56685a7cc 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -1,6 +1,7 @@ + @@ -33,6 +34,7 @@ + From 1d8254daff45ff061c3993a2946f7287f7b5cc28 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Wed, 17 Aug 2022 15:06:09 +0900 Subject: [PATCH 574/851] fix(planning_launch): fix default parameters for lane change decision making (#440) Signed-off-by: Fumiya Watanabe Signed-off-by: Fumiya Watanabe --- .../lane_change/lane_change.param.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml index 86226a95ce..1a66bc09d0 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -12,8 +12,8 @@ prediction_time_resolution: 0.5 static_obstacle_velocity_thresh: 1.5 maximum_deceleration: 1.0 - enable_abort_lane_change: false - enable_collision_check_at_prepare_phase: false - use_predicted_path_outside_lanelet: false - use_all_predicted_path: false + enable_abort_lane_change: true + enable_collision_check_at_prepare_phase: true + use_predicted_path_outside_lanelet: true + use_all_predicted_path: true enable_blocked_by_obstacle: false From 4fc144df5d9ee6c1605383e6923fe040f591f21e Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 18 Aug 2022 13:15:13 +0900 Subject: [PATCH 575/851] fix(ndt_scan_matcher): fix default parameter to 0.0225 (#438) Signed-off-by: kminoda Signed-off-by: kminoda --- localization_launch/config/ndt_scan_matcher.param.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/localization_launch/config/ndt_scan_matcher.param.yaml b/localization_launch/config/ndt_scan_matcher.param.yaml index f5b454a887..8e63ed344b 100644 --- a/localization_launch/config/ndt_scan_matcher.param.yaml +++ b/localization_launch/config/ndt_scan_matcher.param.yaml @@ -55,9 +55,9 @@ # The covariance of output pose output_pose_covariance: [ - 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, - 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, - 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, + 0.0225, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0225, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000625, From 8700c7b59c22b124e1501fd8b0fb39cb1c71c143 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 19 Aug 2022 13:41:17 +0900 Subject: [PATCH 576/851] feat(control_launch): add nearest search param (#442) * feat(control_launch): add nearest search param Signed-off-by: Takayuki Murooka * Update control_launch/launch/control.launch.py Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * fix typo Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> --- .../config/common/nearest_search.param.yaml | 5 +++++ control_launch/launch/control.launch.py | 15 ++++++++++++++- 2 files changed, 19 insertions(+), 1 deletion(-) create mode 100644 control_launch/config/common/nearest_search.param.yaml diff --git a/control_launch/config/common/nearest_search.param.yaml b/control_launch/config/common/nearest_search.param.yaml new file mode 100644 index 0000000000..eb6709764c --- /dev/null +++ b/control_launch/config/common/nearest_search.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + # ego + ego_nearest_dist_threshold: 3.0 # [m] + ego_nearest_yaw_threshold: 1.046 # [rad] = 60 [deg] diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index f948a547ed..66589d5226 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -30,6 +30,9 @@ def launch_setup(context, *args, **kwargs): + nearest_search_param_path = LaunchConfiguration("nearest_search_param_path").perform(context) + with open(nearest_search_param_path, "r") as f: + nearest_search_param = yaml.safe_load(f)["/**"]["ros__parameters"] lat_controller_param_path = LaunchConfiguration("lat_controller_param_path").perform(context) with open(lat_controller_param_path, "r") as f: lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] @@ -73,6 +76,7 @@ def launch_setup(context, *args, **kwargs): "ctrl_period": 0.03, "lateral_controller_mode": LaunchConfiguration("lateral_controller_mode"), }, + nearest_search_param, lon_controller_param, lat_controller_param, ], @@ -95,7 +99,7 @@ def launch_setup(context, *args, **kwargs): "/control/trajectory_follower/lateral/predicted_trajectory", ), ], - parameters=[lane_departure_checker_param], + parameters=[nearest_search_param, lane_departure_checker_param], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) @@ -180,6 +184,7 @@ def launch_setup(context, *args, **kwargs): ("control_mode_request", "/control/control_mode_request"), ], parameters=[ + nearest_search_param, operation_mode_transition_manager_param, ], ) @@ -249,6 +254,14 @@ def add_launch_arg(name: str, default_value=None, description=None): ) # parameter file path + add_launch_arg( + "nearest_search_param_path", + [ + FindPackageShare("control_launch"), + "/config/common/nearest_search.param.yaml", + ], + "path to the parameter file of nearest search", + ) add_launch_arg( "lat_controller_param_path", [ From 164d6944c169b7692724425df9171a31b5ed86d6 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 19 Aug 2022 15:48:05 +0900 Subject: [PATCH 577/851] fix(ekf_localizer): enable enable_yaw_bias (#443) Signed-off-by: kminoda Signed-off-by: kminoda --- .../pose_twist_fusion_filter.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 016838dd0d..0f7883c0e8 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,7 +1,7 @@ - + From 9fe2039c223f6fa6eaefc2ea81966530c4556bd5 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 22 Aug 2022 17:15:12 +0900 Subject: [PATCH 578/851] feat(obstacle_cruise_planner): add velocity_threshold to outside obstacle (#447) Signed-off-by: tomoya.kimura Signed-off-by: tomoya.kimura --- .../obstacle_cruise_planner/obstacle_cruise_planner.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index 63c4a5d9a4..a5d4548b7e 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -50,6 +50,7 @@ collision_time_margin : 8.0 # time threshold of collision between obstacle adn ego for cruise or stop [s] outside_rough_detection_area_expand_width : 0.5 # rough lateral margin for rough detection area expansion for obstacles outside the trajectory [m] + outside_obstacle_min_velocity_threshold : 3.0 # minimum velocity threshold of obstacles outside the trajectory to cruise or stop [m/s] ego_obstacle_overlap_time_threshold : 1.0 # time threshold to decide cut-in obstacle for cruise or stop [s] max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego From c9945c28ec8707d2d935bb418cad8a98dc38828f Mon Sep 17 00:00:00 2001 From: Yusuke Muramatsu Date: Tue, 23 Aug 2022 12:25:25 +0900 Subject: [PATCH 579/851] fix(perception_launch): remove duplicated namespace of clustering in camera-lidar-fusion mode (#449) Signed-off-by: yukke42 Signed-off-by: yukke42 --- .../camera_lidar_fusion_based_detection.launch.xml | 6 +++--- 1 file changed, 3 insertions(+), 3 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 a1fd508dcb..3b6c8388e8 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 @@ -130,9 +130,9 @@ - - - + + + From 0eb6ab35276eca82b79bb062bad197870708d3bd Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Tue, 23 Aug 2022 12:59:53 +0900 Subject: [PATCH 580/851] chore(system_error_monitor): stop syncing parameter for planning_simulator (#446) chore(system_error_monitor): stop to sync parameter for planning_simulator --- .github/sync-param-files.yaml | 4 +- ...ror_monitor.planning_simulation.param.yaml | 50 ------------------- 2 files changed, 2 insertions(+), 52 deletions(-) delete mode 100644 system_launch/config/system_error_monitor.planning_simulation.param.yaml diff --git a/.github/sync-param-files.yaml b/.github/sync-param-files.yaml index ffa78c1690..876c31cf0b 100644 --- a/.github/sync-param-files.yaml +++ b/.github/sync-param-files.yaml @@ -10,8 +10,8 @@ ## system_error_monitor - source: system/system_error_monitor/config/system_error_monitor.param.yaml dest: system_launch/config/system_error_monitor.param.yaml - - source: system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml - dest: system_launch/config/system_error_monitor.planning_simulation.param.yaml + # - source: system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml + # dest: system_launch/config/system_error_monitor.planning_simulation.param.yaml ## system_monitor - source: system/system_monitor/config/cpu_monitor.param.yaml diff --git a/system_launch/config/system_error_monitor.planning_simulation.param.yaml b/system_launch/config/system_error_monitor.planning_simulation.param.yaml deleted file mode 100644 index ce081b75b2..0000000000 --- a/system_launch/config/system_error_monitor.planning_simulation.param.yaml +++ /dev/null @@ -1,50 +0,0 @@ -# Description: -# name: diag name -# sf_at: diag level where it becomes Safe Fault -# lf_at: diag level where it becomes Latent Fault -# spf_at: diag level where it becomes Single Point Fault -# auto_recovery: Determines whether the system will automatically recover when it recovers from an error. -# -# Note: -# empty-value for sf_at, lf_at and spf_at is "none" -# default values are: -# sf_at: "none" -# lf_at: "warn" -# spf_at: "error" -# auto_recovery: "true" ---- -/**: - ros__parameters: - required_modules: - autonomous_driving: - /autoware/control/autonomous_driving/node_alive_monitoring: default - /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default - /autoware/control/control_command_gate/node_alive_monitoring: default - - /autoware/localization/node_alive_monitoring: default - # /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } - # /autoware/localization/performance_monitoring/localization_accuracy: default - - /autoware/map/node_alive_monitoring: default - - /autoware/perception/node_alive_monitoring: default - - /autoware/planning/node_alive_monitoring: default - /autoware/planning/performance_monitoring/trajectory_validation: default - - /autoware/sensing/node_alive_monitoring: default - - /autoware/system/node_alive_monitoring: default - /autoware/system/emergency_stop_operation: default - # /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "error", spf_at: "none" } - - /autoware/vehicle/node_alive_monitoring: default - - external_control: - /autoware/control/control_command_gate/node_alive_monitoring: default - /autoware/control/external_control/external_command_selector/node_alive_monitoring: default - - /autoware/system/node_alive_monitoring: default - /autoware/system/emergency_stop_operation: default - - /autoware/vehicle/node_alive_monitoring: default From 1ae4675295bb7e2951bea7da409f04e880a5bbba Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 24 Aug 2022 10:23:36 +0900 Subject: [PATCH 581/851] feat(behavior_path_planner): change pull_over_velocity (#450) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_over/pull_over.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index d10d63ae3c..fd3c904bb8 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -5,7 +5,7 @@ th_arrived_distance_m: 1.0 th_stopped_velocity_mps: 0.01 th_stopped_time_sec: 2.0 # It must be greater than the state_machine's. - pull_over_velocity: 2.0 + pull_over_velocity: 3.0 pull_over_minimum_velocity: 0.3 margin_from_boundary: 0.5 decide_path_distance: 10.0 From 14f757a8c0481934de174120b22472720d49c07a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 25 Aug 2022 09:40:25 +0900 Subject: [PATCH 582/851] feat(rviz): add 2D dummy bus button as default (#453) Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- autoware_launch/rviz/autoware.rviz | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index c69f0ef925..9461bfe678 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1692,6 +1692,14 @@ Visualization Manager: Y std deviation: 0.029999999329447746 Z position: 0 Z std deviation: 0.029999999329447746 + - Class: rviz_plugins/BusInitialPoseTool + Pose Topic: /simulation/dummy_perception_publisher/object_info + Theta std deviation: 0.0872664600610733 + Velocity: 0 + X std deviation: 0.029999999329447746 + Y std deviation: 0.029999999329447746 + Z position: 0 + Z std deviation: 0.029999999329447746 - Class: rviz_plugins/MissionCheckpointTool Pose Topic: /planning/mission_planning/checkpoint Theta std deviation: 0.2617993950843811 From 8ded8930d0b185cac8ca4a894b1652652a2802c6 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 25 Aug 2022 15:42:40 +0900 Subject: [PATCH 583/851] feat(planning_launch): resample behavior output path (#444) * feat(planning_launch): resample behavior output path Signed-off-by: Takayuki Murooka * update param Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../behavior_path_planner/behavior_path_planner.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index dcfedbadf7..8ba90fd624 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -17,4 +17,6 @@ refine_goal_search_radius_range: 7.5 intersection_search_distance: 30.0 + path_interval: 2.0 + visualize_drivable_area_for_shared_linestrings_lanelet: true From b7039ef5d949fe08b73f306b10ef2e02c0cc7bae Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 25 Aug 2022 19:09:03 +0900 Subject: [PATCH 584/851] feat(planning_launch): add option to output detect polygon for debug (#454) Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- .../surround_obstacle_checker.param.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml index 8354ea60be..982fb7e1d7 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml @@ -10,3 +10,6 @@ # ego stop state stop_state_ego_speed: 0.1 #[m/s] + + # debug + publish_debug_footprints: false # publish vehicle footprint & footprints with surround_check_distance and surround_check_recover_distance offsets From b5a7c89db6dffc79efff582f43b482361a4dc722 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Fri, 26 Aug 2022 17:37:29 +0900 Subject: [PATCH 585/851] feat(run_out): add config of points interval (#455) Signed-off-by: Tomohito Ando Signed-off-by: Tomohito Ando --- .../behavior_velocity_planner/run_out.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml index 527c00ccf3..7bd363ac60 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml @@ -24,6 +24,7 @@ height: 2.0 # [m] height of obstacles. used for creating dynamic obstacles from points max_prediction_time: 10.0 # [sec] create predicted path until this time time_step: 0.5 # [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path + points_interval: 0.1 # [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method # approach if ego has stopped in the front of the obstacle for a certain amount of time approaching: From aaea3c7dd8c1b4bdd5f4a0746aa5ff1ceab40236 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 29 Aug 2022 15:35:14 +0900 Subject: [PATCH 586/851] feat(obstacle_avoidance_planne): enable plan_from_ego by default (#452) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../obstacle_avoidance_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index f31003da09..78abda6861 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -58,7 +58,7 @@ option: steer_limit_constraint: true fix_points_around_ego: true - plan_from_ego: false + plan_from_ego: true max_plan_from_ego_length: 10.0 visualize_sampling_num: 1 enable_manual_warm_start: true From aec72d2ff6de18f5b39990ac337198e0c281c91e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 29 Aug 2022 15:37:15 +0900 Subject: [PATCH 587/851] feat(behavior_path_planner): enable pull_over backward_parking by default (#448) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_over/pull_over.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index fd3c904bb8..777a7cf471 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -12,7 +12,7 @@ min_acc: -0.5 enable_shift_parking: true enable_arc_forward_parking: true - enable_arc_backward_parking: false + enable_arc_backward_parking: true # goal research search_priority: "efficient_path" # "efficient_path" or "close_goal" enable_goal_research: true From d0b004d6b2de3c97eec93f3810eae6e95374920c Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 29 Aug 2022 17:19:23 +0900 Subject: [PATCH 588/851] feat(trajectory_follower): keep stop until the steering control is done (#451) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../trajectory_follower/longitudinal_controller.param.yaml | 2 +- .../config/trajectory_follower/mpc_follower.param.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml index 8ef60c0ef6..bc3213081d 100644 --- a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml +++ b/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml @@ -6,7 +6,7 @@ enable_overshoot_emergency: true enable_large_tracking_error_emergency: true enable_slope_compensation: true - enable_keep_stopped_until_steer_convergence: false + enable_keep_stopped_until_steer_convergence: true # state transition drive_state_stop_dist: 0.5 diff --git a/control_launch/config/trajectory_follower/mpc_follower.param.yaml b/control_launch/config/trajectory_follower/mpc_follower.param.yaml index e8e87e4955..4085f7025b 100644 --- a/control_launch/config/trajectory_follower/mpc_follower.param.yaml +++ b/control_launch/config/trajectory_follower/mpc_follower.param.yaml @@ -56,7 +56,7 @@ stop_state_entry_ego_speed: 0.001 stop_state_entry_target_speed: 0.001 converged_steer_rad: 0.1 - keep_steer_control_until_converged: false + keep_steer_control_until_converged: true new_traj_duration_time: 1.0 new_traj_end_dist: 0.3 From 9cfb34d46d2febcc9db5c35af7b0da560a5ddd9b Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 30 Aug 2022 00:05:43 +0900 Subject: [PATCH 589/851] feat(planning_simulator): new parameters for lane change module (#355) * feat(planning_simulator): new parameters for lane change module Signed-off-by: Muhammad Zulfaqar Azmi * added publish debug marker Signed-off-by: Muhammad Zulfaqar Azmi * reorganize collision check Signed-off-by: Muhammad Zulfaqar Azmi * increase reaction time Signed-off-by: Muhammad Zulfaqar Azmi * Add longitudinal minimum threshold Signed-off-by: Muhammad Zulfaqar Azmi * Set constant color of path candidate to false Signed-off-by: Muhammad Zulfaqar Azmi * Remove parameters from lane_change.param.yaml Signed-off-by: Muhammad Zulfaqar Azmi * include abort parameters Signed-off-by: Muhammad Zulfaqar Azmi * set debug marker publisher to false Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi --- autoware_launch/rviz/autoware.rviz | 2 +- .../behavior_path_planner.param.yaml | 7 ++++++ .../lane_change/lane_change.param.yaml | 24 +++++++++---------- 3 files changed, 20 insertions(+), 13 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 9461bfe678..462c81151b 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1001,7 +1001,7 @@ Visualization Manager: View Path: Alpha: 0.30000001192092896 Color: 115; 210; 22 - Constant Color: true + Constant Color: false Value: true Width: 2 View Velocity: diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index 8ba90fd624..55b531e997 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -20,3 +20,10 @@ path_interval: 2.0 visualize_drivable_area_for_shared_linestrings_lanelet: true + + lateral_distance_max_threshold: 5.0 + longitudinal_distance_min_threshold: 3.0 + expected_front_deceleration: -1.0 + expected_rear_deceleration: -1.0 + rear_vehicle_reaction_time: 2.0 + rear_vehicle_safety_time_margin: 2.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml index 1a66bc09d0..a1ad81b61e 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -1,19 +1,19 @@ /**: ros__parameters: lane_change: - min_stop_distance: 5.0 - stop_time: 2.0 - hysteresis_buffer_distance: 2.0 - lane_change_prepare_duration: 4.0 - lane_changing_duration: 8.0 - lane_change_finish_judge_buffer: 3.0 - minimum_lane_change_velocity: 5.6 - prediction_duration: 8.0 - prediction_time_resolution: 0.5 - static_obstacle_velocity_thresh: 1.5 - maximum_deceleration: 1.0 + lane_change_prepare_duration: 4.0 # [s] + lane_changing_duration: 8.0 # [s] + minimum_lane_change_prepare_distance: 4.0 # [m] + lane_change_finish_judge_buffer: 3.0 # [m] + minimum_lane_change_velocity: 5.6 # [m/s] + prediction_time_resolution: 0.5 # [s] + maximum_deceleration: 1.0 # [m/s2] + lane_change_sampling_num: 10 + abort_lane_change_velocity_thresh: 0.5 + abort_lane_change_angle_thresh: 10.0 # [deg] + abort_lane_change_distance_thresh: 0.3 # [m] enable_abort_lane_change: true enable_collision_check_at_prepare_phase: true use_predicted_path_outside_lanelet: true use_all_predicted_path: true - enable_blocked_by_obstacle: false + publish_debug_marker: false From 3d618f9c1b115c639dc039e6150232e2abb338d6 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 30 Aug 2022 14:35:37 +0900 Subject: [PATCH 590/851] feat(behavior_path_palnner): update geometric parallel parking (#431) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../pull_over/pull_over.param.yaml | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index 777a7cf471..5da3e199cf 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -9,13 +9,10 @@ pull_over_minimum_velocity: 0.3 margin_from_boundary: 0.5 decide_path_distance: 10.0 - min_acc: -0.5 - enable_shift_parking: true - enable_arc_forward_parking: true - enable_arc_backward_parking: true + maximum_deceleration: 0.5 # goal research - search_priority: "efficient_path" # "efficient_path" or "close_goal" enable_goal_research: true + search_priority: "efficient_path" # "efficient_path" or "close_goal" forward_goal_search_length: 20.0 backward_goal_search_length: 20.0 goal_search_interval: 1.0 @@ -25,20 +22,25 @@ theta_size: 360 obstacle_threshold: 60 # shift path + enable_shift_parking: true pull_over_sampling_num: 4 maximum_lateral_jerk: 2.0 minimum_lateral_jerk: 0.5 deceleration_interval: 15.0 - maximum_deceleration: 1.0 after_pull_over_straight_distance: 5.0 before_pull_over_straight_distance: 5.0 # parallel parking path + enable_arc_forward_parking: true + enable_arc_backward_parking: true after_forward_parking_straight_distance: 2.0 after_backward_parking_straight_distance: 2.0 forward_parking_velocity: 0.3 backward_parking_velocity: -0.3 + forward_parking_lane_departure_margin: 0.0 + backward_parking_lane_departure_margin: 0.0 arc_path_interval: 1.0 - # hazard. Not used now. + max_steer_rad: 0.35 # 20deg + # hazard on when parked hazard_on_threshold_dis: 1.0 hazard_on_threshold_vel: 0.5 # check safety with dynamic objects. Not used now. From 33820f5ba657722ed6908ebc6799838af63b450c Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 31 Aug 2022 00:40:07 +0900 Subject: [PATCH 591/851] feat(intersection): continue detection after pass judge (#456) Signed-off-by: Mamoru Sobue --- .../behavior_velocity_planner/intersection.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index 2f8ebad3ba..f4948901ed 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -3,6 +3,8 @@ intersection: state_transit_margin_time: 0.5 stop_line_margin: 3.0 + keep_detection_line_margin: 1.0 # distance (toward path end) from generated stop line. keep detection if ego is before this line and ego.vel < keep_detection_vel_thr + keep_detection_vel_thr: 0.833 # == 3.0km/h stuck_vehicle_detect_dist: 3.0 # this should be the length between cars when they are stopped. The actual stuck vehicle detection length will be this value + vehicle_length. stuck_vehicle_ignore_dist: 7.0 # obstacle stop max distance(5.0m) + stuck vehicle size / 2 (0.0m-) stuck_vehicle_vel_thr: 0.833 # 0.833m/s = 3.0km/h From ba3d9fff0f46b951a95ca0c7dfa9b266dd35ce41 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Wed, 31 Aug 2022 15:37:29 +0900 Subject: [PATCH 592/851] chore: sync files (#429) * chore: sync files Signed-off-by: GitHub * Update sync-files.yaml Signed-off-by: GitHub Co-authored-by: kenji-miyake Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .github/sync-files.yaml | 1 + .github/workflows/build-and-test-differential.yaml | 7 ++----- .yamllint.yaml | 1 - 3 files changed, 3 insertions(+), 6 deletions(-) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 181be61423..dd291a8235 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -19,3 +19,4 @@ files: - source: .github/workflows/build-and-test.yaml - source: .github/workflows/build-and-test-differential.yaml + - source: .github/workflows/cancel-previous-workflows.yaml diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 746d6bd3ba..9dbdf7b77f 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -21,9 +21,6 @@ jobs: container: ros:humble build-depends-repos: build_depends.repos steps: - - name: Cancel previous runs - uses: styfle/cancel-workflow-action@0.10.0 - - name: Check out repository uses: actions/checkout@v3 with: @@ -64,7 +61,7 @@ jobs: clang-tidy-differential: runs-on: ubuntu-latest - container: ros:galactic + container: ros:humble needs: build-and-test-differential steps: - name: Check out repository @@ -83,7 +80,7 @@ jobs: if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} uses: autowarefoundation/autoware-github-actions/clang-tidy@v1 with: - rosdistro: galactic + rosdistro: humble target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy build-depends-repos: build_depends.repos diff --git a/.yamllint.yaml b/.yamllint.yaml index 6228c70f02..2c7bd088e2 100644 --- a/.yamllint.yaml +++ b/.yamllint.yaml @@ -1,7 +1,6 @@ extends: default ignore: | - .clang-tidy *.param.yaml rules: From dfafa9cf11e7c939f359862af1928ebc1b247c10 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 1 Sep 2022 02:26:13 +0900 Subject: [PATCH 593/851] refactor(behavior_path_planner): rename pull_over params (#460) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_over/pull_over.param.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index 5da3e199cf..d11ed1f0db 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -2,9 +2,9 @@ ros__parameters: pull_over: request_length: 100.0 - th_arrived_distance_m: 1.0 - th_stopped_velocity_mps: 0.01 - th_stopped_time_sec: 2.0 # It must be greater than the state_machine's. + th_arrived_distance: 1.0 + th_stopped_velocity: 0.01 + th_stopped_time: 2.0 # It must be greater than the state_machine's. pull_over_velocity: 3.0 pull_over_minimum_velocity: 0.3 margin_from_boundary: 0.5 @@ -39,7 +39,7 @@ forward_parking_lane_departure_margin: 0.0 backward_parking_lane_departure_margin: 0.0 arc_path_interval: 1.0 - max_steer_rad: 0.35 # 20deg + pull_over_max_steer_angle: 0.35 # 20deg # hazard on when parked hazard_on_threshold_dis: 1.0 hazard_on_threshold_vel: 0.5 From 6d85263c3fc840897a3c6e94e11ee74bb499fff0 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Thu, 1 Sep 2022 09:33:05 +0900 Subject: [PATCH 594/851] chore: sync files (#461) Signed-off-by: GitHub Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/cancel-previous-workflows.yaml | 14 ++++++++++++++ 1 file changed, 14 insertions(+) create mode 100644 .github/workflows/cancel-previous-workflows.yaml diff --git a/.github/workflows/cancel-previous-workflows.yaml b/.github/workflows/cancel-previous-workflows.yaml new file mode 100644 index 0000000000..aeb34c6a03 --- /dev/null +++ b/.github/workflows/cancel-previous-workflows.yaml @@ -0,0 +1,14 @@ +name: cancel-previous-workflows + +on: + pull_request_target: + +jobs: + cancel-previous-workflows: + runs-on: ubuntu-latest + steps: + - name: Cancel previous runs + uses: styfle/cancel-workflow-action@0.10.0 + with: + workflow_id: all + all_but_latest: true From 21a4dbe4cbe5f810765d1a26447588a1423bcf13 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 1 Sep 2022 13:24:41 +0900 Subject: [PATCH 595/851] feat(rviz): add behavior path debug markers (#462) Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- autoware_launch/rviz/autoware.rviz | 64 +++++++++++++++++++++++++++++- 1 file changed, 62 insertions(+), 2 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 462c81151b..6e00b81365 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1307,7 +1307,7 @@ Visualization Manager: Value: false - Class: rviz_default_plugins/MarkerArray Enabled: false - Name: BehaviorPath + Name: Avoidance Namespaces: {} Topic: @@ -1315,7 +1315,67 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/markers + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: LaneChange + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lanechange + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: LaneFollowing + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lanefollowing + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: PullOver + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/pullover + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: PullOut + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/pullout + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: SideShift + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/sideshift Value: false - Class: rviz_common/Group Displays: From 04158441add9bca21ff143dbd3e7c1d71625eeeb Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 2 Sep 2022 19:00:41 +0900 Subject: [PATCH 596/851] feat(behavior_path_planner): update pull out (#439) * feat(behavior_path_planner): update pull out Signed-off-by: kosuke55 * rename params Signed-off-by: kosuke55 * add search priority Signed-off-by: kosuke55 * change before_pull_out_straight_distance to 0.0 Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../pull_out/pull_out.param.yaml | 41 +++++++++++-------- 1 file changed, 23 insertions(+), 18 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml index 434545674d..7a9a63f805 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml @@ -1,25 +1,30 @@ /**: ros__parameters: pull_out: - min_stop_distance: 2.0 - stop_time: 0.0 - hysteresis_buffer_distance: 1.0 - pull_out_prepare_duration: 4.0 - pull_out_duration: 2.0 + th_arrived_distance: 1.0 + th_stopped_velocity: 0.01 + th_stopped_time: 1.0 + collision_check_margin: 1.0 pull_out_finish_judge_buffer: 1.0 - minimum_pull_out_velocity: 2.0 - prediction_duration: 30.0 - prediction_time_resolution: 0.5 - static_obstacle_velocity_thresh: 1.5 - maximum_deceleration: 1.0 - enable_collision_check_at_prepare_phase: false - use_predicted_path_outside_lanelet: false - use_all_predicted_path: false - use_dynamic_object: true - enable_blocked_by_obstacle: false - pull_out_search_distance: 30.0 - before_pull_out_straight_distance: 5.0 - after_pull_out_straight_distance: 5.0 + # shift pull out + enable_shift_pull_out: true + shift_pull_out_velocity: 2.0 + pull_out_sampling_num: 4 + before_pull_out_straight_distance: 0.0 + minimum_shift_pull_out_distance: 20.0 maximum_lateral_jerk: 2.0 minimum_lateral_jerk: 0.5 deceleration_interval: 15.0 + # geometric pull out + enable_geometric_pull_out: true + geometric_pull_out_velocity: 1.0 + arc_path_interval: 1.0 + lane_departure_margin: 0.2 + backward_velocity: -1.0 + pull_out_max_steer_angle: 0.26 # 15deg + # search start pose backward + enable_back: true + search_priority: "efficient_path" # "efficient_path" or "short_back_distance" + max_back_distance: 15.0 + backward_search_resolution: 2.0 + backward_path_update_duration: 3.0 From 4f9ce80b0a2f1c5e7a1cb221eb688d2a44c08b18 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sun, 4 Sep 2022 12:54:26 +0900 Subject: [PATCH 597/851] chore: sync files (#463) Signed-off-by: GitHub Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 9dbdf7b77f..b322f4f19a 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -76,11 +76,20 @@ jobs: id: get-modified-packages uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1 + - name: Get modified files + id: get-modified-files + uses: tj-actions/changed-files@v28 + with: + files: | + **/*.cpp + **/*.hpp + - name: Run clang-tidy - if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} + if: ${{ steps.get-modified-files.outputs.all_changed_files != '' }} uses: autowarefoundation/autoware-github-actions/clang-tidy@v1 with: rosdistro: humble target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + target-files: ${{ steps.get-modified-files.outputs.all_changed_files }} clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy build-depends-repos: build_depends.repos From ffcb2a638348e4df01ce5258a9bacb04cd57d0b8 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 5 Sep 2022 18:09:10 +0900 Subject: [PATCH 598/851] feat(behavior_path_planner): use object recognition for pull_over (#464) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_over/pull_over.param.yaml | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index d11ed1f0db..baa35d2a88 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -18,9 +18,13 @@ goal_search_interval: 1.0 goal_to_obj_margin: 2.0 # occupancy grid map - collision_check_margin: 0.5 + use_occupancy_grid: true + occupancy_grid_collision_check_margin: 0.0 theta_size: 360 obstacle_threshold: 60 + # object recognition + use_object_recognition: true + object_recognition_collision_check_margin: 1.0 # shift path enable_shift_parking: true pull_over_sampling_num: 4 From dcea545834c96a3d2d8e42285c8dc2f2bbf31cf6 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 6 Sep 2022 15:13:31 +0900 Subject: [PATCH 599/851] fix(behavior_path_planner): fix pull_over request_length and maximum_deceleration (#468) fix(behavior_path_planner): fix request_length and maximum_deceleration Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_over/pull_over.param.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index baa35d2a88..8aba3d305c 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: pull_over: - request_length: 100.0 + request_length: 200.0 th_arrived_distance: 1.0 th_stopped_velocity: 0.01 th_stopped_time: 2.0 # It must be greater than the state_machine's. @@ -9,7 +9,7 @@ pull_over_minimum_velocity: 0.3 margin_from_boundary: 0.5 decide_path_distance: 10.0 - maximum_deceleration: 0.5 + maximum_deceleration: 1.0 # goal research enable_goal_research: true search_priority: "efficient_path" # "efficient_path" or "close_goal" From ef611e086fba879c4a28d90a2e020e44bea9af58 Mon Sep 17 00:00:00 2001 From: Takeshi Ishita Date: Tue, 6 Sep 2022 18:42:02 +0900 Subject: [PATCH 600/851] fix(localization_launch): rename biased pose topics (#469) fix(localization_launch): rename biased yaw topics --- .../launch/pose_estimator/pose_estimator.launch.xml | 2 +- .../pose_twist_fusion_filter.launch.xml | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml index 7e9d0ab8d2..3273db453f 100644 --- a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml +++ b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml @@ -4,7 +4,7 @@ - + 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 0f7883c0e8..9988df4cef 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 @@ -11,8 +11,8 @@ - - + + From 3145c5d8a8a9350ca52869ab812f8dc94aee4cca Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 6 Sep 2022 19:17:30 +0900 Subject: [PATCH 601/851] refactor(planning_launch): update params name for readability (#458) * refactor(planning_launch): update params name for readability Signed-off-by: satoshi-ota * refactor(planning_launch): add params to config Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- .../obstacle_stop_planner.param.yaml | 65 ++++++++++++------- 1 file changed, 43 insertions(+), 22 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml index 36421cf37a..55a21d6cd7 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml @@ -1,28 +1,49 @@ /**: ros__parameters: - hunting_threshold: 0.5 # even if the obstacle disappears, the stop judgment continues for hunting_threshold [s] + hunting_threshold: 0.5 # even if the obstacle disappears, the stop judgment continues for hunting_threshold [s] + lowpass_gain: 0.9 # gain parameter for low pass filter [-] + max_velocity: 20.0 # max velocity [m/s] + enable_slow_down: False # whether to use slow down planner [-] 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] - hold_stop_margin_distance: 0.0 # the ego keeps stopping if the ego is in this margin [m] + # params for stop position + stop_position: + max_longitudinal_margin: 5.0 # stop margin distance from obstacle on the path [m] + min_longitudinal_margin: 5.0 # stop margin distance when any other stop point is inserted in stop margin [m] + hold_stop_margin_distance: 0.0 # the ego keeps stopping if the ego is in this margin [m] + + # params for detection area + detection_area: + lateral_margin: 0.0 # margin of vehicle footprint [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 [m] + slow_down_planner: - # slow down planner parameters - forward_margin: 5.0 # margin distance from slow down point to vehicle front [m] - backward_margin: 0.0 # margin distance from slow down point to vehicle rear [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] - - # slow down constraint parameters - consider_constraints: False # set "True", if no decel plan found under jerk/dec constrains, relax target slow down vel - forward_margin_min: 1.0 # min margin for relaxing slow down margin [m/s] - forward_margin_span: -0.1 # fineness param for relaxing slow down margin [m/s] - jerk_min_slow_down: -0.6 # min slow down jerk constraint [m/sss] - jerk_span: -0.01 # fineness param for planning deceleration jerk [m/sss] - jerk_start: -0.1 # init jerk used for deceleration planning [m/sss] - slow_down_vel: 1.38 # target slow down velocity [m/s] + # params for slow down section + slow_down_section: + longitudinal_forward_margin: 5.0 # margin distance from slow down point to vehicle front [m] + longitudinal_backward_margin: 0.0 # margin distance from slow down point to vehicle rear [m] + longitudinal_margin_span: -0.1 # fineness param for relaxing slow down margin (use this param if consider_constraints is True) [m/s] + min_longitudinal_forward_margin: 1.0 # min margin for relaxing slow down margin (use this param if consider_constraints is True) [m/s] + + # params for detection area + detection_area: + lateral_margin: 1.0 # offset from vehicle side edge for expanding the search area of the surrounding point cloud [m] + + # params for velocity + target_velocity: + max_slow_down_velocity: 1.38 # max slow down velocity (use this param if consider_constraints is False)[m/s] + min_slow_down_velocity: 0.28 # min slow down velocity (use this param if consider_constraints is False)[m/s] + slow_down_velocity: 1.38 # target slow down velocity (use this param if consider_constraints is True)[m/s] + + # params for deceleration constraints (use this param if consider_constraints is True) + constraints: + jerk_min_slow_down: -0.6 # min slow down jerk constraint [m/sss] + jerk_span: -0.01 # fineness param for planning deceleration jerk [m/sss] + jerk_start: -0.1 # init jerk used for deceleration planning [m/sss] + + # others + consider_constraints: False # set "True", if no decel plan found under jerk/dec constrains, relax target slow down vel [-] + velocity_threshold_decel_complete: 0.2 # use for judge whether the ego velocity converges the target slow down velocity [m/s] + acceleration_threshold_decel_complete: 0.1 # use for judge whether the ego velocity converges the target slow down velocity [m/ss] From defaa300ef3d0256c611ff7d5da500fc502d7744 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Wed, 7 Sep 2022 09:38:54 +0900 Subject: [PATCH 602/851] feat: add launch for vector map inside area filter (#459) Signed-off-by: Tomohito Ando Signed-off-by: Tomohito Ando --- .../behavior_planning.launch.py | 43 ++++++--- .../behavior_planning/compare_map.launch.py | 4 +- .../vector_map_inside_area_filter.launch.py | 88 +++++++++++++++++++ 3 files changed, 121 insertions(+), 14 deletions(-) create mode 100644 planning_launch/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index d0b92a4627..011d1061bd 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -419,6 +419,19 @@ def generate_launch_description(): condition=IfCondition(LaunchConfiguration("use_multithread")), ) + # This condition is true if run_out module is enabled and its detection method is Points + launch_run_out_with_points_method = PythonExpression( + [ + LaunchConfiguration( + "launch_run_out", default=behavior_velocity_planner_param["launch_run_out"] + ), + " and ", + "'", + run_out_param["run_out"]["detection_method"], + "' == 'Points'", + ] + ) + # load compare map for run out module load_compare_map = IncludeLaunchDescription( PythonLaunchDescriptionSource( @@ -433,19 +446,24 @@ def generate_launch_description(): "use_multithread": "true", }.items(), # launch compare map only when run_out module is enabled and detection method is Points - condition=IfCondition( - PythonExpression( - [ - LaunchConfiguration( - "launch_run_out", default=behavior_velocity_planner_param["launch_run_out"] - ), - " and ", - "'", - run_out_param["run_out"]["detection_method"], - "' == 'Points'", - ] - ) + condition=IfCondition(launch_run_out_with_points_method), + ) + + load_vector_map_inside_area_filter = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + FindPackageShare("tier4_planning_launch"), + "/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py", + ] ), + launch_arguments={ + "use_pointcloud_container": LaunchConfiguration("use_pointcloud_container"), + "container_name": LaunchConfiguration("container_name"), + "use_multithread": "true", + "polygon_type": "no_obstacle_segmentation_area_for_run_out", + }.items(), + # launch vector map filter only when run_out module is enabled and detection method is Points + condition=IfCondition(launch_run_out_with_points_method), ) return launch.LaunchDescription( @@ -460,5 +478,6 @@ def generate_launch_description(): set_container_mt_executable, container, load_compare_map, + load_vector_map_inside_area_filter, ] ) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py index fe3e347fd2..60b31f475e 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py @@ -45,7 +45,7 @@ def add_launch_arg(name: str, default_value=None): plugin="compare_map_segmentation::VoxelDistanceBasedCompareMapFilterComponent", name="voxel_distance_based_compare_map_filter_node", remappings=[ - ("input", "/perception/obstacle_segmentation/pointcloud"), + ("input", "vector_map_inside_area_filtered/pointcloud"), ("map", "/map/pointcloud_map"), ("output", "compare_map_filtered/pointcloud"), ], @@ -61,7 +61,7 @@ def add_launch_arg(name: str, default_value=None): ] compare_map_container = ComposableNodeContainer( - name=LaunchConfiguration("container_name"), + name="compare_map_container", namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py new file mode 100644 index 0000000000..3921dcfe7d --- /dev/null +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py @@ -0,0 +1,88 @@ +# Copyright 2022 TIER IV, Inc. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import SetLaunchConfiguration +from launch.conditions import IfCondition +from launch.conditions import UnlessCondition +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import LoadComposableNodes +from launch_ros.descriptions import ComposableNode + + +def generate_launch_description(): + def add_launch_arg(name: str, default_value=None): + return DeclareLaunchArgument(name, default_value=default_value) + + set_container_executable = SetLaunchConfiguration( + "container_executable", + "component_container", + condition=UnlessCondition(LaunchConfiguration("use_multithread")), + ) + + set_container_mt_executable = SetLaunchConfiguration( + "container_executable", + "component_container_mt", + condition=IfCondition(LaunchConfiguration("use_multithread")), + ) + + composable_nodes = [ + ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::VectorMapInsideAreaFilterComponent", + name="vector_map_inside_area_filter_node", + remappings=[ + ("input", "/perception/obstacle_segmentation/pointcloud"), + ("input/vector_map", "/map/vector_map"), + ("output", "vector_map_inside_area_filtered/pointcloud"), + ], + parameters=[ + { + "polygon_type": LaunchConfiguration("polygon_type"), + } + ], + # this node has QoS of transient local + extra_arguments=[{"use_intra_process_comms": False}], + ), + ] + + vector_map_area_filter_container = ComposableNodeContainer( + name="vector_map_area_filter_container", + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=composable_nodes, + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), + output="screen", + ) + + load_composable_nodes = LoadComposableNodes( + composable_node_descriptions=composable_nodes, + target_container=LaunchConfiguration("container_name"), + condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), + ) + + return LaunchDescription( + [ + add_launch_arg("use_multithread", "true"), + add_launch_arg("use_pointcloud_container", "true"), + add_launch_arg("container_name", "vector_map_area_filter_container"), + set_container_executable, + set_container_mt_executable, + vector_map_area_filter_container, + load_composable_nodes, + ] + ) From 82c2f81ed86c640cdf28fb257c3c5cb3bd1101bc Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 7 Sep 2022 10:20:11 +0900 Subject: [PATCH 603/851] feat(behavior_path_planner): check goal to objects logitudinal distance for pull_over (#470) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_over/pull_over.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index 8aba3d305c..0231003e24 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -16,7 +16,7 @@ forward_goal_search_length: 20.0 backward_goal_search_length: 20.0 goal_search_interval: 1.0 - goal_to_obj_margin: 2.0 + goal_to_obstacle_margin: 2.0 # occupancy grid map use_occupancy_grid: true occupancy_grid_collision_check_margin: 0.0 From 9b2c680ef23f3d183baa2343d09ab8d282a48290 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 8 Sep 2022 18:53:28 +0900 Subject: [PATCH 604/851] chore(system_error_monitor): stop syncing parameter for planning_simulator (#446) (#472) chore(system_error_monitor): stop to sync parameter for planning_simulator --- .github/sync-param-files.yaml | 4 +- ...ror_monitor.planning_simulation.param.yaml | 50 ------------------- 2 files changed, 2 insertions(+), 52 deletions(-) delete mode 100644 system_launch/config/system_error_monitor.planning_simulation.param.yaml diff --git a/.github/sync-param-files.yaml b/.github/sync-param-files.yaml index ffa78c1690..876c31cf0b 100644 --- a/.github/sync-param-files.yaml +++ b/.github/sync-param-files.yaml @@ -10,8 +10,8 @@ ## system_error_monitor - source: system/system_error_monitor/config/system_error_monitor.param.yaml dest: system_launch/config/system_error_monitor.param.yaml - - source: system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml - dest: system_launch/config/system_error_monitor.planning_simulation.param.yaml + # - source: system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml + # dest: system_launch/config/system_error_monitor.planning_simulation.param.yaml ## system_monitor - source: system/system_monitor/config/cpu_monitor.param.yaml diff --git a/system_launch/config/system_error_monitor.planning_simulation.param.yaml b/system_launch/config/system_error_monitor.planning_simulation.param.yaml deleted file mode 100644 index ce081b75b2..0000000000 --- a/system_launch/config/system_error_monitor.planning_simulation.param.yaml +++ /dev/null @@ -1,50 +0,0 @@ -# Description: -# name: diag name -# sf_at: diag level where it becomes Safe Fault -# lf_at: diag level where it becomes Latent Fault -# spf_at: diag level where it becomes Single Point Fault -# auto_recovery: Determines whether the system will automatically recover when it recovers from an error. -# -# Note: -# empty-value for sf_at, lf_at and spf_at is "none" -# default values are: -# sf_at: "none" -# lf_at: "warn" -# spf_at: "error" -# auto_recovery: "true" ---- -/**: - ros__parameters: - required_modules: - autonomous_driving: - /autoware/control/autonomous_driving/node_alive_monitoring: default - /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default - /autoware/control/control_command_gate/node_alive_monitoring: default - - /autoware/localization/node_alive_monitoring: default - # /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } - # /autoware/localization/performance_monitoring/localization_accuracy: default - - /autoware/map/node_alive_monitoring: default - - /autoware/perception/node_alive_monitoring: default - - /autoware/planning/node_alive_monitoring: default - /autoware/planning/performance_monitoring/trajectory_validation: default - - /autoware/sensing/node_alive_monitoring: default - - /autoware/system/node_alive_monitoring: default - /autoware/system/emergency_stop_operation: default - # /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "error", spf_at: "none" } - - /autoware/vehicle/node_alive_monitoring: default - - external_control: - /autoware/control/control_command_gate/node_alive_monitoring: default - /autoware/control/external_control/external_command_selector/node_alive_monitoring: default - - /autoware/system/node_alive_monitoring: default - /autoware/system/emergency_stop_operation: default - - /autoware/vehicle/node_alive_monitoring: default From ce9ad9f017f7566b2113134c31e8a8811ec95e0e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 8 Sep 2022 23:37:59 +0900 Subject: [PATCH 605/851] feat(behavior_path_planner): change pull over params (#473) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../pull_over/pull_over.param.yaml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index 0231003e24..98488a82d8 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -6,7 +6,7 @@ th_stopped_velocity: 0.01 th_stopped_time: 2.0 # It must be greater than the state_machine's. pull_over_velocity: 3.0 - pull_over_minimum_velocity: 0.3 + pull_over_minimum_velocity: 1.38 margin_from_boundary: 0.5 decide_path_distance: 10.0 maximum_deceleration: 1.0 @@ -15,8 +15,8 @@ search_priority: "efficient_path" # "efficient_path" or "close_goal" forward_goal_search_length: 20.0 backward_goal_search_length: 20.0 - goal_search_interval: 1.0 - goal_to_obstacle_margin: 2.0 + goal_search_interval: 2.0 + goal_to_obstacle_margin: 3.0 # occupancy grid map use_occupancy_grid: true occupancy_grid_collision_check_margin: 0.0 @@ -38,8 +38,8 @@ enable_arc_backward_parking: true after_forward_parking_straight_distance: 2.0 after_backward_parking_straight_distance: 2.0 - forward_parking_velocity: 0.3 - backward_parking_velocity: -0.3 + forward_parking_velocity: 1.38 + backward_parking_velocity: -1.38 forward_parking_lane_departure_margin: 0.0 backward_parking_lane_departure_margin: 0.0 arc_path_interval: 1.0 From cf05a8870805d11bf74bb0bc1b700cf9ad10ae87 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Fri, 9 Sep 2022 10:53:43 +0900 Subject: [PATCH 606/851] chore: sync param files (#474) Signed-off-by: GitHub Signed-off-by: GitHub Co-authored-by: kenji-miyake --- system_launch/config/system_monitor/net_monitor.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/system_launch/config/system_monitor/net_monitor.param.yaml b/system_launch/config/system_monitor/net_monitor.param.yaml index 953d32d788..686ee349b0 100644 --- a/system_launch/config/system_monitor/net_monitor.param.yaml +++ b/system_launch/config/system_monitor/net_monitor.param.yaml @@ -3,3 +3,5 @@ devices: ["*"] traffic_reader_port: 7636 monitor_program: "greengrass" + crc_error_check_duration: 1 + crc_error_count_threshold: 1 From 2d379a018fd8a681fa54ac8c3fb3b8a7ad135f36 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Fri, 9 Sep 2022 11:19:38 +0900 Subject: [PATCH 607/851] feat(obstacle_cruise_planner): add parameters for collison check (#471) * feat(obstacle_cruise_planner): add parameters for collison check Signed-off-by: yutaka * change paramters Signed-off-by: yutaka Signed-off-by: yutaka --- .../obstacle_cruise_planner.param.yaml | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index a5d4548b7e..91779111d4 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -54,11 +54,14 @@ ego_obstacle_overlap_time_threshold : 1.0 # time threshold to decide cut-in obstacle for cruise or stop [s] max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego - stop_obstacle_hold_time_threshold : 1.0 # maximum time for holding closest stop obstacle - prediction_resampling_time_interval: 0.1 prediction_resampling_time_horizon: 10.0 + goal_extension_length: 5.0 # extension length for collision check around the goal + goal_extension_interval: 1.0 # extension interval for collision check around the goal + + stop_obstacle_hold_time_threshold : 1.0 # maximum time for holding closest stop obstacle + ignored_outside_obstacle_type: unknown: true car: false From cf775a64fd6a587ae2d5e0508acb6214f8d663ec Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Mon, 12 Sep 2022 15:52:17 +0900 Subject: [PATCH 608/851] ci: add backport.yaml to sync-files.yaml (#477) --- .github/sync-files.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index dd291a8235..2c91ce5316 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -1,6 +1,7 @@ - repository: autowarefoundation/autoware files: - source: .github/dependabot.yaml + - source: .github/workflows/backport.yaml - source: .github/workflows/github-release.yaml - source: .github/workflows/pre-commit.yaml - source: .github/workflows/pre-commit-optional.yaml From 8695c6e4254621757b2cd6223058757a58030787 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Mon, 12 Sep 2022 16:06:09 +0900 Subject: [PATCH 609/851] ci: add backport.yaml to sync-files.yaml (copy #477) (#479) ci: add backport.yaml to sync-files.yaml (#477) (cherry picked from commit cf775a64fd6a587ae2d5e0508acb6214f8d663ec) Co-authored-by: Hiroki OTA --- .github/sync-files.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index dd291a8235..2c91ce5316 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -1,6 +1,7 @@ - repository: autowarefoundation/autoware files: - source: .github/dependabot.yaml + - source: .github/workflows/backport.yaml - source: .github/workflows/github-release.yaml - source: .github/workflows/pre-commit.yaml - source: .github/workflows/pre-commit-optional.yaml From 59a3665414d4eeb0fe24062cc5d14cba7be27ded Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Mon, 12 Sep 2022 16:06:55 +0900 Subject: [PATCH 610/851] chore: sync files (#478) Signed-off-by: GitHub Signed-off-by: GitHub Co-authored-by: h-ohta --- .github/workflows/backport.yaml | 26 ++++++++++++++++++++++++++ 1 file changed, 26 insertions(+) create mode 100644 .github/workflows/backport.yaml diff --git a/.github/workflows/backport.yaml b/.github/workflows/backport.yaml new file mode 100644 index 0000000000..01eafed32c --- /dev/null +++ b/.github/workflows/backport.yaml @@ -0,0 +1,26 @@ +name: backport +on: + pull_request_target: + types: + - closed + - labeled + +jobs: + backport: + runs-on: ubuntu-latest + # Only react to merged PRs for security reasons. + # See https://docs.github.com/en/actions/using-workflows/events-that-trigger-workflows#pull_request_target. + if: > + github.event.pull_request.merged + && ( + github.event.action == 'closed' + || ( + github.event.action == 'labeled' + && contains(github.event.label.name, 'backport') + ) + ) + steps: + - uses: tibdex/backport@v2 + with: + github_token: ${{ secrets.GITHUB_TOKEN }} + title_template: "<%= title %> (backport #<%= number %>)" From daf3d1c6bcf80e426f60541809b869291ccd4c36 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 13 Sep 2022 11:46:46 +0900 Subject: [PATCH 611/851] feat(rviz): remove old pull over marker (#480) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- autoware_launch/rviz/autoware.rviz | 37 ------------------------------ 1 file changed, 37 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 6e00b81365..ce17aef92d 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1377,43 +1377,6 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/sideshift Value: false - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: GoalSearchArea - Namespaces: - collision_polygons: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/debug/parking_area - Value: false - - Alpha: 0.9990000128746033 - Arrow Length: 0.30000001192092896 - Axes Length: 0.30000001192092896 - Axes Radius: 0.009999999776482582 - Class: rviz_default_plugins/PoseArray - Color: 255; 25; 0 - Enabled: false - Head Length: 0.10000000149011612 - Head Radius: 0.20000000298023224 - Name: PullOverPathPoseArray - Shaft Length: 0.20000000298023224 - Shaft Radius: 0.05000000074505806 - Shape: Arrow (3D) - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/debug/path_pose_array - Value: false - Enabled: false - Name: PullOver Enabled: false Name: DebugMarker Enabled: true From 6098a73d257bbacb690ce1322e53d4c9ab7b19b1 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 14 Sep 2022 16:25:28 +0900 Subject: [PATCH 612/851] feat(planning_launch): use acceleration from localization module (#482) * feat(planning_launch): subscribe acceleration from localization module Signed-off-by: satoshi-ota * feat(planning_launch): subscribe acceleration from localization module Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- .../lane_driving/behavior_planning/behavior_planning.launch.py | 2 ++ .../lane_driving/behavior_planning/behavior_planning.launch.xml | 1 + 2 files changed, 3 insertions(+) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 011d1061bd..f3955b1aab 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -142,6 +142,7 @@ def generate_launch_description(): ("~/input/vector_map", LaunchConfiguration("map_topic_name")), ("~/input/perception", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), + ("~/input/accel", "/localization/acceleration"), ("~/input/scenario", "/planning/scenario_planning/scenario"), ("~/output/path", "path_with_lane_id"), ("~/output/turn_indicators_cmd", "/planning/turn_indicators_cmd"), @@ -342,6 +343,7 @@ def generate_launch_description(): ("~/input/path_with_lane_id", "path_with_lane_id"), ("~/input/vector_map", "/map/vector_map"), ("~/input/vehicle_odometry", "/localization/kinematic_state"), + ("~/input/accel", "/localization/acceleration"), ("~/input/dynamic_objects", "/perception/object_recognition/objects"), ( "~/input/no_ground_pointcloud", 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 9922f6c15d..a16b2f56cb 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 @@ -7,6 +7,7 @@ + From 5b3d44f2eab36889fd066c634319dc740f469453 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 14 Sep 2022 20:16:58 +0900 Subject: [PATCH 613/851] feat(shift_decider): add auto-park when arrived goal (#483) Signed-off-by: Takamasa Horibe Signed-off-by: Takamasa Horibe --- control_launch/launch/control.launch.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 66589d5226..d160c8ec05 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -110,8 +110,14 @@ def launch_setup(context, *args, **kwargs): name="shift_decider", remappings=[ ("input/control_cmd", "/control/trajectory_follower/control_cmd"), + ("input/state", "/autoware/state"), ("output/gear_cmd", "/control/shift_decider/gear_cmd"), ], + parameters=[ + { + "park_on_goal": True, + } + ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) From de49ece38ce92a705377411255f5c641c5ec93e5 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 14 Sep 2022 21:18:03 +0900 Subject: [PATCH 614/851] feat(shift_decider): add shift decider config (#484) Signed-off-by: Takamasa Horibe Signed-off-by: Takamasa Horibe --- .../shift_decider/shift_decider.param.yaml | 3 +++ control_launch/launch/control.launch.py | 16 +++++++++++++--- control_launch/launch/control.launch.xml | 2 ++ 3 files changed, 18 insertions(+), 3 deletions(-) create mode 100644 control_launch/config/shift_decider/shift_decider.param.yaml diff --git a/control_launch/config/shift_decider/shift_decider.param.yaml b/control_launch/config/shift_decider/shift_decider.param.yaml new file mode 100644 index 0000000000..4c45b36223 --- /dev/null +++ b/control_launch/config/shift_decider/shift_decider.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + park_on_goal: true diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index d160c8ec05..2681df4db8 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -56,6 +56,10 @@ def launch_setup(context, *args, **kwargs): with open(operation_mode_transition_manager_param_path, "r") as f: operation_mode_transition_manager_param = yaml.safe_load(f)["/**"]["ros__parameters"] + shift_decider_param_path = LaunchConfiguration("shift_decider_param_path").perform(context) + with open(shift_decider_param_path, "r") as f: + shift_decider_param = yaml.safe_load(f)["/**"]["ros__parameters"] + controller_component = ComposableNode( package="trajectory_follower_nodes", plugin="autoware::motion::control::trajectory_follower_nodes::Controller", @@ -114,9 +118,7 @@ def launch_setup(context, *args, **kwargs): ("output/gear_cmd", "/control/shift_decider/gear_cmd"), ], parameters=[ - { - "park_on_goal": True, - } + shift_decider_param, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) @@ -304,6 +306,14 @@ def add_launch_arg(name: str, default_value=None, description=None): ], "path to the parameter file of vehicle_cmd_gate", ) + add_launch_arg( + "shift_decider_param_path", + [ + FindPackageShare("control_launch"), + "/config/shift_decider/shift_decider_param.param.yaml", + ], + "path to the parameter file of shift_decider", + ) # vehicle cmd gate add_launch_arg("use_emergency_handling", "false", "use emergency handling") diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index 90974363ea..54ceac8262 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -6,6 +6,7 @@ + @@ -14,6 +15,7 @@ + From e9ba1544fa90167d87bf47b52ac5f39058177da2 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 15 Sep 2022 11:15:07 +0900 Subject: [PATCH 615/851] feat(planning_launch): add rtc_auto_mode_manager (#433) Signed-off-by: Fumiya Watanabe Signed-off-by: Fumiya Watanabe --- .../rtc_auto_approver.param.yaml | 29 ------------------- .../rtc_auto_mode_manager.param.yaml | 29 +++++++++++++++++++ .../scenario_planning/lane_driving.launch.xml | 6 ++-- 3 files changed, 32 insertions(+), 32 deletions(-) delete mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_approver/rtc_auto_approver.param.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_approver/rtc_auto_approver.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_approver/rtc_auto_approver.param.yaml deleted file mode 100644 index 5b98c1c070..0000000000 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_approver/rtc_auto_approver.param.yaml +++ /dev/null @@ -1,29 +0,0 @@ -/**: - ros__parameters: - module_list: - - "behavior_velocity_planner/blind_spot" - - "behavior_velocity_planner/crosswalk" - - "behavior_velocity_planner/detection_area" - - "behavior_velocity_planner/intersection" - - "behavior_velocity_planner/no_stopping_area" - - "behavior_velocity_planner/traffic_light" - - "behavior_path_planner/lane_change_left" - - "behavior_path_planner/lane_change_right" - - "behavior_path_planner/avoidance_left" - - "behavior_path_planner/avoidance_right" - - "behavior_path_planner/pull_over" - - "behavior_path_planner/pull_out" - - default_enable_list: - - "behavior_velocity_planner/blind_spot" - - "behavior_velocity_planner/crosswalk" - - "behavior_velocity_planner/detection_area" - - "behavior_velocity_planner/intersection" - - "behavior_velocity_planner/no_stopping_area" - - "behavior_velocity_planner/traffic_light" - - "behavior_path_planner/lane_change_left" - - "behavior_path_planner/lane_change_right" - - "behavior_path_planner/avoidance_left" - - "behavior_path_planner/avoidance_right" - - "behavior_path_planner/pull_over" - - "behavior_path_planner/pull_out" diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml new file mode 100644 index 0000000000..8ba0a402ee --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml @@ -0,0 +1,29 @@ +/**: + ros__parameters: + module_list: + - "blind_spot" + - "crosswalk" + - "detection_area" + - "intersection" + - "no_stopping_area" + - "traffic_light" + - "lane_change_left" + - "lane_change_right" + - "avoidance_left" + - "avoidance_right" + - "pull_over" + - "pull_out" + + default_enable_list: + - "blind_spot" + - "crosswalk" + - "detection_area" + - "intersection" + - "no_stopping_area" + - "traffic_light" + - "lane_change_left" + - "lane_change_right" + - "avoidance_left" + - "avoidance_right" + - "pull_over" + - "pull_out" diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch.xml b/planning_launch/launch/scenario_planning/lane_driving.launch.xml index a0e35c5874..e232b7a0af 100644 --- a/planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving.launch.xml @@ -17,9 +17,9 @@ - - - + + + From 1d712d039c0984842a3024eb3d62838190a76b18 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 15 Sep 2022 21:40:44 +0900 Subject: [PATCH 616/851] feat(obstacle_avoidance_planner): fix can be applied to the first trajectory point (#476) * update param Signed-off-by: Takayuki Murooka * update param Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../obstacle_avoidance_planner.param.yaml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 78abda6861..50f5caa048 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -63,6 +63,7 @@ visualize_sampling_num: 1 enable_manual_warm_start: true enable_warm_start: true # false + is_fixed_point_single: false common: num_curvature_sampling_points: 5 # number of sampling points when calculating curvature @@ -148,3 +149,8 @@ num_for_calculation: 3 front_radius_ratio: 1.0 rear_radius_ratio: 1.0 + + bicycle_model: + num_for_calculation: 3 + front_radius_ratio: 1.0 + rear_radius_ratio: 1.0 From a529247357559e951b349d24ac29ddf74218228d Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Fri, 16 Sep 2022 13:18:59 +0900 Subject: [PATCH 617/851] docs(README): add description to archive this repository --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index b22428a818..70b5757004 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,5 @@ # autoware_launcher +This repository is an archived repository. Please check here for the details. ## Getting started From 8b7e7bf7c622937eedd6eb5bb24f1fa2e9190e68 Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Fri, 16 Sep 2022 13:22:33 +0900 Subject: [PATCH 618/851] Revert "docs(README): add description to archive this repository" This reverts commit a529247357559e951b349d24ac29ddf74218228d. --- README.md | 1 - 1 file changed, 1 deletion(-) diff --git a/README.md b/README.md index 70b5757004..b22428a818 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,4 @@ # autoware_launcher -This repository is an archived repository. Please check here for the details. ## Getting started From 31f48d98135b01d87f63b5546fd7abc324eb3918 Mon Sep 17 00:00:00 2001 From: Kah Hooi Tan <41041286+tkhmy@users.noreply.github.com> Date: Fri, 16 Sep 2022 15:14:09 +0900 Subject: [PATCH 619/851] feat: sync launch for init pose (#486) * add rviz helper for ad api Signed-off-by: khtan * sync for init pose Signed-off-by: khtan * add missing sync Signed-off-by: khtan * add rviz adaptor Signed-off-by: Takagi, Isamu * fix launch_dummy_localization Signed-off-by: Takagi, Isamu * add dependency Signed-off-by: Takagi, Isamu * add dependency Signed-off-by: Takagi, Isamu * ci(pre-commit): autofix Signed-off-by: khtan Signed-off-by: Takagi, Isamu Co-authored-by: Takagi, Isamu Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- autoware_api_launch/launch/autoware_api.launch.xml | 6 ++++++ .../launch/include/internal_api_adaptor.launch.py | 6 ------ .../launch/include/internal_api_relay.launch.xml | 6 ------ autoware_api_launch/package.xml | 1 + autoware_launch/launch/autoware.launch.xml | 6 ++---- autoware_launch/launch/logging_simulator.launch.xml | 6 ++---- autoware_launch/launch/planning_simulator.launch.xml | 9 +++++---- autoware_launch/package.xml | 1 + localization_launch/launch/util/util.launch.xml | 7 ++++++- localization_launch/package.xml | 1 + simulator_launch/launch/simulator.launch.xml | 10 ++++++++++ ...ervice_state_monitor.planning_simulation.param.yaml | 4 ++-- 12 files changed, 36 insertions(+), 27 deletions(-) diff --git a/autoware_api_launch/launch/autoware_api.launch.xml b/autoware_api_launch/launch/autoware_api.launch.xml index c3562857fe..45c1f62d12 100644 --- a/autoware_api_launch/launch/autoware_api.launch.xml +++ b/autoware_api_launch/launch/autoware_api.launch.xml @@ -1,6 +1,12 @@ + + + + + + diff --git a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py index 4b8513f544..422c35abee 100644 --- a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py @@ -13,7 +13,6 @@ # limitations under the License. import launch -from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer from launch_ros.descriptions import ComposableNode @@ -29,12 +28,7 @@ def _create_api_node(node_name, class_name, **kwargs): def generate_launch_description(): - param_initial_pose = { - "init_simulator_pose": LaunchConfiguration("init_simulator_pose"), - "init_localization_pose": LaunchConfiguration("init_localization_pose"), - } components = [ - _create_api_node("initial_pose", "InitialPose", parameters=[param_initial_pose]), _create_api_node("iv_msgs", "IVMsgs"), _create_api_node("operator", "Operator"), _create_api_node("route", "Route"), diff --git a/autoware_api_launch/launch/include/internal_api_relay.launch.xml b/autoware_api_launch/launch/include/internal_api_relay.launch.xml index 810e6a566b..e850fb3dc4 100644 --- a/autoware_api_launch/launch/include/internal_api_relay.launch.xml +++ b/autoware_api_launch/launch/include/internal_api_relay.launch.xml @@ -16,11 +16,5 @@ - - - - - - diff --git a/autoware_api_launch/package.xml b/autoware_api_launch/package.xml index 5777880654..71a37f44f0 100644 --- a/autoware_api_launch/package.xml +++ b/autoware_api_launch/package.xml @@ -12,6 +12,7 @@ autoware_iv_external_api_adaptor autoware_iv_internal_api_adaptor awapi_awiv_adapter + default_ad_api path_distance_calculator topic_tools diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index d4975c6464..5f2af36436 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -95,10 +95,7 @@ - - - - + @@ -112,6 +109,7 @@ args="-d $(find-pkg-share autoware_launch)/rviz/autoware.rviz -s $(find-pkg-share autoware_launch)/rviz/image/autoware.png" if="$(var rviz)" /> + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index c143f2c51b..3a360d460f 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -111,10 +111,7 @@ - - - - + @@ -128,6 +125,7 @@ args="-d $(find-pkg-share autoware_launch)/rviz/autoware.rviz -s $(find-pkg-share autoware_launch)/rviz/image/autoware.png" if="$(var rviz)" /> + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index e9cb8c5f1e..b7fb373d5b 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -68,10 +68,7 @@ - - - - + @@ -85,6 +82,7 @@ args="-d $(var rviz_config) -s $(find-pkg-share autoware_launch)/rviz/image/autoware.png" if="$(var rviz)" /> + @@ -96,10 +94,13 @@ + + + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index fa7f7aad14..037f453faa 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -9,6 +9,7 @@ ament_cmake_auto + ad_api_adaptors autoware_api_launch control_launch global_parameter_loader diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 4b80a343da..783eee8adc 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -7,7 +7,12 @@ - + + + + + + diff --git a/localization_launch/package.xml b/localization_launch/package.xml index a6dbe359ce..c61aaeed79 100644 --- a/localization_launch/package.xml +++ b/localization_launch/package.xml @@ -11,6 +11,7 @@ ament_cmake_auto + automatic_pose_initializer ekf_localizer gyro_odometer ndt_scan_matcher diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index 5ebe48cd9c..08d27a73b1 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -1,6 +1,7 @@ + @@ -74,6 +75,15 @@ + + + + + + + + + diff --git a/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml b/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml index b20ffec096..51fbe99dd9 100644 --- a/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml +++ b/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml @@ -24,7 +24,7 @@ names: [ "/map/vector_map", "/perception/object_recognition/objects", - "/initialpose2d", + "/initialpose3d", "/planning/mission_planning/route", "/planning/scenario_planning/trajectory", "/control/trajectory_follower/control_cmd", @@ -48,7 +48,7 @@ warn_rate: 5.0 type: "autoware_auto_perception_msgs/msg/PredictedObjects" - /initialpose2d: + /initialpose3d: module: "localization" timeout: 0.0 warn_rate: 0.0 From 62578e42b6ec0cd931b1872d632214e57cc788c6 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Sat, 17 Sep 2022 15:23:58 +0900 Subject: [PATCH 620/851] refactor: rename acc topic (#398) * refactor: rename acc topic Signed-off-by: Takamasa Horibe * remove lpf_gain param Signed-off-by: Takamasa Horibe Signed-off-by: Takamasa Horibe --- control_launch/launch/control.launch.py | 1 + .../obstacle_cruise_planner/obstacle_cruise_planner.param.yaml | 2 -- .../lane_driving/motion_planning/motion_planning.launch.py | 2 ++ 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 2681df4db8..361ff8c695 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -69,6 +69,7 @@ def launch_setup(context, *args, **kwargs): ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), ("~/input/current_odometry", "/localization/kinematic_state"), ("~/input/current_steering", "/vehicle/status/steering_status"), + ("~/input/current_accel", "/localization/acceleration"), ("~/output/predicted_trajectory", "lateral/predicted_trajectory"), ("~/output/lateral_diagnostic", "lateral/diagnostic"), ("~/output/slope_angle", "longitudinal/slope_angle"), diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index 91779111d4..ebb190f8eb 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -11,8 +11,6 @@ min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] safe_distance_margin : 6.0 # This is also used as a stop margin [m] - lpf_gain_for_accel: 0.2 # gain of low pass filter for ego acceleration [-] - nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index min_behavior_stop_margin: 3.0 # [m] diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index fc1859eb76..db68a478cf 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -140,6 +140,7 @@ def generate_launch_description(): remappings=[ ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), ("~/input/odometry", "/localization/kinematic_state"), + ("~/input/acceleration", "/localization/acceleration"), ("~/input/objects", "/perception/object_recognition/objects"), ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), ("~/output/velocity_limit", "/planning/scenario_planning/max_velocity_candidates"), @@ -191,6 +192,7 @@ def generate_launch_description(): "/planning/scenario_planning/clear_velocity_limit", ), ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), + ("~/input/acceleration", "/localization/acceleration"), ( "~/input/pointcloud", "/perception/obstacle_segmentation/pointcloud", From 23f773bed08647d997387acde54cdf467a3be010 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Tue, 20 Sep 2022 12:13:11 +0900 Subject: [PATCH 621/851] feat(perception_launch): update tracking parameter (#488) * feat(multi_object_tracker): increase max-area for truck Signed-off-by: tomoya.kimura * feat(multi_object_tracker): update bus size Signed-off-by: tomoya.kimura Signed-off-by: tomoya.kimura --- .../data_association_matrix.param.yaml | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml index 6fb495c258..1790315ae5 100644 --- a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml +++ b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml @@ -22,12 +22,14 @@ 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #BICYCLE 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN max_area_matrix: + # NOTE(yukke42): The size of truck is 12 m length x 3 m width. + # NOTE(yukke42): The size of trailer is 20 m length x 3 m width. #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN - [10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, #UNKNOWN - 12.10, 12.10, 19.75, 40.00, 40.00, 10000.00, 10000.00, 10000.00, #CAR - 19.75, 12.10, 19.75, 40.00, 40.00, 10000.00, 10000.00, 10000.00, #TRUCK - 40.00, 12.10, 19.75, 40.00, 40.00, 10000.00, 10000.00, 10000.00, #BUS - 40.00, 12.10, 19.75, 40.00, 40.00, 10000.00, 10000.00, 10000.00, #TRAILER + [100.00, 100.00, 100.00, 100.00, 100.00, 100.00, 100.00, 100.00, #UNKNOWN + 12.10, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #CAR + 36.00, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #TRUCK + 60.00, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #BUS + 60.00, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #TRAILER 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #MOTORBIKE 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #BICYCLE 2.00, 10000.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00] #PEDESTRIAN From 9917a1b8c59e2fd8df14352536881753fa950529 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Fri, 16 Sep 2022 13:18:59 +0900 Subject: [PATCH 622/851] docs(README): add description to archive this repository --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index b22428a818..70b5757004 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,5 @@ # autoware_launcher +This repository is an archived repository. Please check here for the details. ## Getting started From d2faafd1199d0f0be43242c37f98732cb6fecc75 Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Fri, 16 Sep 2022 13:22:33 +0900 Subject: [PATCH 623/851] Revert "docs(README): add description to archive this repository" This reverts commit a529247357559e951b349d24ac29ddf74218228d. --- README.md | 1 - 1 file changed, 1 deletion(-) diff --git a/README.md b/README.md index 70b5757004..b22428a818 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,4 @@ # autoware_launcher -This repository is an archived repository. Please check here for the details. ## Getting started From 913abba0d234b90a88956f2a638a2a1e2dca8de4 Mon Sep 17 00:00:00 2001 From: Kah Hooi Tan <41041286+tkhmy@users.noreply.github.com> Date: Fri, 16 Sep 2022 15:14:09 +0900 Subject: [PATCH 624/851] feat: sync launch for init pose (#486) * add rviz helper for ad api Signed-off-by: khtan * sync for init pose Signed-off-by: khtan * add missing sync Signed-off-by: khtan * add rviz adaptor Signed-off-by: Takagi, Isamu * fix launch_dummy_localization Signed-off-by: Takagi, Isamu * add dependency Signed-off-by: Takagi, Isamu * add dependency Signed-off-by: Takagi, Isamu * ci(pre-commit): autofix Signed-off-by: khtan Signed-off-by: Takagi, Isamu Co-authored-by: Takagi, Isamu Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- autoware_api_launch/launch/autoware_api.launch.xml | 6 ++++++ .../launch/include/internal_api_adaptor.launch.py | 6 ------ .../launch/include/internal_api_relay.launch.xml | 6 ------ autoware_api_launch/package.xml | 1 + autoware_launch/launch/autoware.launch.xml | 6 ++---- autoware_launch/launch/logging_simulator.launch.xml | 6 ++---- autoware_launch/launch/planning_simulator.launch.xml | 9 +++++---- autoware_launch/package.xml | 1 + localization_launch/launch/util/util.launch.xml | 7 ++++++- localization_launch/package.xml | 1 + simulator_launch/launch/simulator.launch.xml | 10 ++++++++++ ...ervice_state_monitor.planning_simulation.param.yaml | 4 ++-- 12 files changed, 36 insertions(+), 27 deletions(-) diff --git a/autoware_api_launch/launch/autoware_api.launch.xml b/autoware_api_launch/launch/autoware_api.launch.xml index c3562857fe..45c1f62d12 100644 --- a/autoware_api_launch/launch/autoware_api.launch.xml +++ b/autoware_api_launch/launch/autoware_api.launch.xml @@ -1,6 +1,12 @@ + + + + + + diff --git a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py index 4b8513f544..422c35abee 100644 --- a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py @@ -13,7 +13,6 @@ # limitations under the License. import launch -from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer from launch_ros.descriptions import ComposableNode @@ -29,12 +28,7 @@ def _create_api_node(node_name, class_name, **kwargs): def generate_launch_description(): - param_initial_pose = { - "init_simulator_pose": LaunchConfiguration("init_simulator_pose"), - "init_localization_pose": LaunchConfiguration("init_localization_pose"), - } components = [ - _create_api_node("initial_pose", "InitialPose", parameters=[param_initial_pose]), _create_api_node("iv_msgs", "IVMsgs"), _create_api_node("operator", "Operator"), _create_api_node("route", "Route"), diff --git a/autoware_api_launch/launch/include/internal_api_relay.launch.xml b/autoware_api_launch/launch/include/internal_api_relay.launch.xml index 810e6a566b..e850fb3dc4 100644 --- a/autoware_api_launch/launch/include/internal_api_relay.launch.xml +++ b/autoware_api_launch/launch/include/internal_api_relay.launch.xml @@ -16,11 +16,5 @@ - - - - - - diff --git a/autoware_api_launch/package.xml b/autoware_api_launch/package.xml index 5777880654..71a37f44f0 100644 --- a/autoware_api_launch/package.xml +++ b/autoware_api_launch/package.xml @@ -12,6 +12,7 @@ autoware_iv_external_api_adaptor autoware_iv_internal_api_adaptor awapi_awiv_adapter + default_ad_api path_distance_calculator topic_tools diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index d4975c6464..5f2af36436 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -95,10 +95,7 @@ - - - - + @@ -112,6 +109,7 @@ args="-d $(find-pkg-share autoware_launch)/rviz/autoware.rviz -s $(find-pkg-share autoware_launch)/rviz/image/autoware.png" if="$(var rviz)" /> + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index c143f2c51b..3a360d460f 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -111,10 +111,7 @@ - - - - + @@ -128,6 +125,7 @@ args="-d $(find-pkg-share autoware_launch)/rviz/autoware.rviz -s $(find-pkg-share autoware_launch)/rviz/image/autoware.png" if="$(var rviz)" /> + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index e9cb8c5f1e..b7fb373d5b 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -68,10 +68,7 @@ - - - - + @@ -85,6 +82,7 @@ args="-d $(var rviz_config) -s $(find-pkg-share autoware_launch)/rviz/image/autoware.png" if="$(var rviz)" /> + @@ -96,10 +94,13 @@ + + + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index fa7f7aad14..037f453faa 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -9,6 +9,7 @@ ament_cmake_auto + ad_api_adaptors autoware_api_launch control_launch global_parameter_loader diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 4b80a343da..783eee8adc 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -7,7 +7,12 @@ - + + + + + + diff --git a/localization_launch/package.xml b/localization_launch/package.xml index a6dbe359ce..c61aaeed79 100644 --- a/localization_launch/package.xml +++ b/localization_launch/package.xml @@ -11,6 +11,7 @@ ament_cmake_auto + automatic_pose_initializer ekf_localizer gyro_odometer ndt_scan_matcher diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index 5ebe48cd9c..08d27a73b1 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -1,6 +1,7 @@ + @@ -74,6 +75,15 @@ + + + + + + + + + diff --git a/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml b/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml index b20ffec096..51fbe99dd9 100644 --- a/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml +++ b/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml @@ -24,7 +24,7 @@ names: [ "/map/vector_map", "/perception/object_recognition/objects", - "/initialpose2d", + "/initialpose3d", "/planning/mission_planning/route", "/planning/scenario_planning/trajectory", "/control/trajectory_follower/control_cmd", @@ -48,7 +48,7 @@ warn_rate: 5.0 type: "autoware_auto_perception_msgs/msg/PredictedObjects" - /initialpose2d: + /initialpose3d: module: "localization" timeout: 0.0 warn_rate: 0.0 From 7c8bba4672ededd5975ee20389fe6c6d39cb0036 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Sat, 17 Sep 2022 15:23:58 +0900 Subject: [PATCH 625/851] refactor: rename acc topic (#398) * refactor: rename acc topic Signed-off-by: Takamasa Horibe * remove lpf_gain param Signed-off-by: Takamasa Horibe Signed-off-by: Takamasa Horibe --- control_launch/launch/control.launch.py | 1 + .../obstacle_cruise_planner/obstacle_cruise_planner.param.yaml | 2 -- .../lane_driving/motion_planning/motion_planning.launch.py | 2 ++ 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 2681df4db8..361ff8c695 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -69,6 +69,7 @@ def launch_setup(context, *args, **kwargs): ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), ("~/input/current_odometry", "/localization/kinematic_state"), ("~/input/current_steering", "/vehicle/status/steering_status"), + ("~/input/current_accel", "/localization/acceleration"), ("~/output/predicted_trajectory", "lateral/predicted_trajectory"), ("~/output/lateral_diagnostic", "lateral/diagnostic"), ("~/output/slope_angle", "longitudinal/slope_angle"), diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index 91779111d4..ebb190f8eb 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -11,8 +11,6 @@ min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] safe_distance_margin : 6.0 # This is also used as a stop margin [m] - lpf_gain_for_accel: 0.2 # gain of low pass filter for ego acceleration [-] - nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index min_behavior_stop_margin: 3.0 # [m] diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index fc1859eb76..db68a478cf 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -140,6 +140,7 @@ def generate_launch_description(): remappings=[ ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), ("~/input/odometry", "/localization/kinematic_state"), + ("~/input/acceleration", "/localization/acceleration"), ("~/input/objects", "/perception/object_recognition/objects"), ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), ("~/output/velocity_limit", "/planning/scenario_planning/max_velocity_candidates"), @@ -191,6 +192,7 @@ def generate_launch_description(): "/planning/scenario_planning/clear_velocity_limit", ), ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), + ("~/input/acceleration", "/localization/acceleration"), ( "~/input/pointcloud", "/perception/obstacle_segmentation/pointcloud", From dbb4d419b0ab57a1fcbb31f5fb49973f6c2da40f Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 22 Sep 2022 17:05:51 +0900 Subject: [PATCH 626/851] feat(intersection): use intersection area if available (#467) Signed-off-by: Mamoru Sobue --- .../behavior_velocity_planner/intersection.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index f4948901ed..cd563ab9e9 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -14,6 +14,7 @@ detection_area_right_margin: 0.5 # [m] detection_area_left_margin: 0.5 # [m] detection_area_length: 200.0 # [m] + detection_area_angle_threshold: 0.785 # [rad] min_predicted_path_confidence: 0.05 collision_start_margin_time: 5.0 # [s] collision_end_margin_time: 2.0 # [s] From 5cb85ef57200d3def24c7b31a6cb9b434ccf73de Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Fri, 23 Sep 2022 12:32:35 +0900 Subject: [PATCH 627/851] chore: sync files (#492) Signed-off-by: GitHub Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index b322f4f19a..434ccb7916 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -78,7 +78,7 @@ jobs: - name: Get modified files id: get-modified-files - uses: tj-actions/changed-files@v28 + uses: tj-actions/changed-files@v29 with: files: | **/*.cpp From 6d8ad14d6e840c15fbff1c6a35ea86ca8c27cc15 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 27 Sep 2022 10:22:11 +0900 Subject: [PATCH 628/851] feat(behavior_path_planner): add pull_over base class (#491) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_over/pull_over.param.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index 98488a82d8..281d91f574 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -45,8 +45,8 @@ arc_path_interval: 1.0 pull_over_max_steer_angle: 0.35 # 20deg # hazard on when parked - hazard_on_threshold_dis: 1.0 - hazard_on_threshold_vel: 0.5 + hazard_on_threshold_distance: 1.0 + hazard_on_threshold_velocity: 0.5 # check safety with dynamic objects. Not used now. pull_over_duration: 2.0 pull_over_prepare_duration: 4.0 From 2d440f867e6ee74889e9cce3fd06367a7d1a28d9 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 27 Sep 2022 12:20:56 +0900 Subject: [PATCH 629/851] fix(autoware_launch): enable dummy_localization (#494) Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- autoware_launch/launch/planning_simulator.launch.xml | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index b7fb373d5b..6b099fa824 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -94,8 +94,7 @@ - - + From e29c879fcdbbefbb125064048d11f7ceb321d721 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 27 Sep 2022 17:35:22 +0900 Subject: [PATCH 630/851] chore: sync files (#493) Signed-off-by: GitHub Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 434ccb7916..cd4b384ac1 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -78,7 +78,7 @@ jobs: - name: Get modified files id: get-modified-files - uses: tj-actions/changed-files@v29 + uses: tj-actions/changed-files@v31 with: files: | **/*.cpp From 9edf6568f84e6023065978650629713a4185651f Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Tue, 27 Sep 2022 18:08:20 +0900 Subject: [PATCH 631/851] chore(run_out): update parameter (#495) Signed-off-by: Tomohito Ando Signed-off-by: Tomohito Ando --- .../behavior_velocity_planner/run_out.param.yaml | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml index 7bd363ac60..44f623b96b 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml @@ -7,7 +7,6 @@ stop_margin: 2.5 # [m] the vehicle decelerates to be able to stop with this margin passing_margin: 1.1 # [m] the vehicle begins to accelerate if the vehicle's front in predicted position is ahead of the obstacle + this margin deceleration_jerk: -0.3 # [m/s^3] ego decelerates with this jerk when stopping for obstacles - obstacle_velocity_kph: 5.0 # [km/h] assumption for obstacle velocity detection_distance: 45.0 # [m] ahead distance from ego to detect the obstacles detection_span: 1.0 # [m] calculate collision with this span to reduce calculation time min_vel_ego_kmph: 3.6 # [km/h] min velocity to calculate time to collision @@ -31,9 +30,12 @@ enable: false margin: 0.0 # [m] distance on how close ego approaches the obstacle limit_vel_kmph: 3.0 # [km/h] limit velocity for approaching after stopping - stop_thresh: 0.01 # [m/s] threshold to decide if ego is stopping - stop_time_thresh: 3.0 # [sec] threshold for stopping time to transit to approaching state - dist_thresh: 0.5 # [m] end the approaching state if distance to the obstacle is longer than stop_margin + dist_thresh + + # parameters for the change of state. used only when approaching is enabled + state: + stop_thresh: 0.01 # [m/s] threshold to decide if ego is stopping + stop_time_thresh: 3.0 # [sec] threshold for stopping time to transit to approaching state + disable_approach_dist: 3.0 # [m] end the approaching state if distance to the obstacle is longer than this value # parameter to avoid sudden stopping slow_down_limit: From d66f77f16e34313d53d401518d92e0da1af8a8ae Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Fri, 30 Sep 2022 13:28:18 +0900 Subject: [PATCH 632/851] feat(perception_launch): add enable_fine_detection option (#499) Signed-off-by: Shumpei Wakabayashi Signed-off-by: Shumpei Wakabayashi --- perception_launch/launch/perception.launch.xml | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 9bfd185631..858eb56688 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -31,6 +31,8 @@ /> + + @@ -120,7 +122,9 @@ - + + + From 4b17a77ef9cc68b364bf0aaf188099cc24403a1e Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Wed, 5 Oct 2022 11:17:23 +0900 Subject: [PATCH 633/851] chore: sync files (#498) Signed-off-by: GitHub Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/backport.yaml | 9 ++++++++- .github/workflows/cancel-previous-workflows.yaml | 2 +- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/.github/workflows/backport.yaml b/.github/workflows/backport.yaml index 01eafed32c..7a9d63f79c 100644 --- a/.github/workflows/backport.yaml +++ b/.github/workflows/backport.yaml @@ -20,7 +20,14 @@ jobs: ) ) steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + - uses: tibdex/backport@v2 with: - github_token: ${{ secrets.GITHUB_TOKEN }} + github_token: ${{ steps.generate-token.outputs.token }} title_template: "<%= title %> (backport #<%= number %>)" diff --git a/.github/workflows/cancel-previous-workflows.yaml b/.github/workflows/cancel-previous-workflows.yaml index aeb34c6a03..b28a4ec0bb 100644 --- a/.github/workflows/cancel-previous-workflows.yaml +++ b/.github/workflows/cancel-previous-workflows.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Cancel previous runs - uses: styfle/cancel-workflow-action@0.10.0 + uses: styfle/cancel-workflow-action@0.10.1 with: workflow_id: all all_but_latest: true From 5915d175fe8e9ed24326382925c6e3d4a81d81ae Mon Sep 17 00:00:00 2001 From: Azumi Suzuki <38061530+s-azumi@users.noreply.github.com> Date: Thu, 6 Oct 2022 09:46:04 +0900 Subject: [PATCH 634/851] fix: modified to reflect the argument "initial_selector_mode" in control launch (#496) --- control_launch/launch/control.launch.py | 2 +- control_launch/launch/control.launch.xml | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 361ff8c695..13e5a7dd51 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -206,7 +206,7 @@ def launch_setup(context, *args, **kwargs): launch_arguments=[ ("use_intra_process", LaunchConfiguration("use_intra_process")), ("target_container", "/control/control_container"), - ("initial_selector_mode", "remote"), + ("initial_selector_mode", LaunchConfiguration("initial_selector_mode")), ], ) diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index 54ceac8262..a833d24a95 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -7,6 +7,7 @@ + @@ -16,6 +17,7 @@ + From 9c7eb5d29f2eaf23b71309e021f6df6416a245f5 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Fri, 7 Oct 2022 02:41:25 +0900 Subject: [PATCH 635/851] feat(obstacle_cruise_planner): add goal safe distance (#503) --- .../obstacle_cruise_planner/obstacle_cruise_planner.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index ebb190f8eb..ddbc714fb3 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -10,6 +10,7 @@ min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] safe_distance_margin : 6.0 # This is also used as a stop margin [m] + terminal_safe_distance_margin : 3.0 # Stop margin at the goal [m] nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index From 2d78c4c075426fe5933f4d00f0c7b88fd9878c39 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Fri, 7 Oct 2022 11:15:30 +0900 Subject: [PATCH 636/851] chore: sync files (#504) Signed-off-by: GitHub Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index cd4b384ac1..a44ef48d1d 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -78,7 +78,7 @@ jobs: - name: Get modified files id: get-modified-files - uses: tj-actions/changed-files@v31 + uses: tj-actions/changed-files@v32 with: files: | **/*.cpp From 0be98d559d4347d373bbe0d3e7db6eea2c2eea0c Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Fri, 7 Oct 2022 14:53:45 +0900 Subject: [PATCH 637/851] chore(run_out): update parameters for run out (#497) Signed-off-by: Tomohito Ando Signed-off-by: Tomohito Ando --- .../behavior_velocity_planner/run_out.param.yaml | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml index 44f623b96b..ccf90a0b29 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml @@ -33,9 +33,10 @@ # parameters for the change of state. used only when approaching is enabled state: - stop_thresh: 0.01 # [m/s] threshold to decide if ego is stopping - stop_time_thresh: 3.0 # [sec] threshold for stopping time to transit to approaching state - disable_approach_dist: 3.0 # [m] end the approaching state if distance to the obstacle is longer than this value + stop_thresh: 0.01 # [m/s] threshold to decide if ego is stopping + stop_time_thresh: 3.0 # [sec] threshold for stopping time to transit to approaching state + disable_approach_dist: 3.0 # [m] end the approaching state if distance to the obstacle is longer than this value + keep_approach_duration: 1.0 # [sec] keep approach state for this duration to avoid chattering of state transition # parameter to avoid sudden stopping slow_down_limit: From 1b30cb5fb20c4027da9c379d97085bd7e62138ac Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Fri, 7 Oct 2022 16:57:03 +0900 Subject: [PATCH 638/851] feat(planning_launch): add explanation (#506) Signed-off-by: yutaka Signed-off-by: yutaka --- .../obstacle_cruise_planner/obstacle_cruise_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index ddbc714fb3..ad2462c790 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -10,7 +10,7 @@ min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] safe_distance_margin : 6.0 # This is also used as a stop margin [m] - terminal_safe_distance_margin : 3.0 # Stop margin at the goal [m] + terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m] nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index From 3803155f3402338fa6e970f2ad76ee7646f7ce34 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Fri, 7 Oct 2022 19:34:02 +0900 Subject: [PATCH 639/851] feat: add api launch option to logsim (#508) Signed-off-by: tanaka3 Signed-off-by: tanaka3 --- autoware_launch/launch/logging_simulator.launch.xml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 3a360d460f..1e06453a48 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -8,6 +8,7 @@ + @@ -111,7 +112,7 @@ - + From 9e89a68f3fd17812cd88095382ad160c7d72a5a5 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 11 Oct 2022 12:24:07 +0900 Subject: [PATCH 640/851] feat(behavior_path_planner): pull_over lateral goal search (#507) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_over/pull_over.param.yaml | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index 281d91f574..8e277959bc 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -16,9 +16,12 @@ forward_goal_search_length: 20.0 backward_goal_search_length: 20.0 goal_search_interval: 2.0 - goal_to_obstacle_margin: 3.0 + longitudinal_margin: 3.0 + max_lateral_offset: 1.0 + lateral_offset_interval: 0.25 # occupancy grid map use_occupancy_grid: true + use_occupancy_grid_for_longitudinal_margin: false occupancy_grid_collision_check_margin: 0.0 theta_size: 360 obstacle_threshold: 60 From ce52d89fa615dc78d0528b781436e053ab96a3c2 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Thu, 13 Oct 2022 15:46:37 +0900 Subject: [PATCH 641/851] feat(control_launch): add longitudinal controller option (#514) * feat(control_launch): add longitudinal controller option Signed-off-by: tanaka3 * ci(pre-commit): autofix Signed-off-by: tanaka3 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- control_launch/launch/control.launch.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 361ff8c695..1d84fc6b31 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -262,6 +262,13 @@ def add_launch_arg(name: str, default_value=None, description=None): "lateral controller mode: `mpc_follower` or `pure_pursuit`", ) + # longitudinal controller mode + add_launch_arg( + "longitudinal_controller_mode", + "pid", + "longitudinal controller mode: `pid`", + ) + # parameter file path add_launch_arg( "nearest_search_param_path", From 52e7e8d1bf5785d13850ace8d9aef9e6ea4eea06 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 14 Oct 2022 09:27:44 +0900 Subject: [PATCH 642/851] feat(localization_launch): sync with awf/universe (add twist2accel, add group tag) (#515) --- .../pose_twist_fusion_filter.launch.xml | 58 +++++++++++-------- 1 file changed, 35 insertions(+), 23 deletions(-) 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 9988df4cef..3c109769e1 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,28 +1,40 @@ - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - - - - + + + + + + + + - - - - - - - - - + + + + + + + + From e13997eb6ca62f62ced7055376335876ea6c8afa Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Fri, 14 Oct 2022 22:56:23 +0900 Subject: [PATCH 643/851] fix(ground_segmentation): add param for grid scan_ground_filter (#509) * fix: add param for grid scan_ground_filter Signed-off-by: badai-nguyen * chore: unify parameters as universe launch Signed-off-by: badai-nguyen * fix search package name Signed-off-by: Shunsuke Miura Signed-off-by: badai-nguyen Signed-off-by: Shunsuke Miura Co-authored-by: Shunsuke Miura Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --- .../ground_segmentation.param.yaml | 12 ++++++++++-- .../ground_segmentation.launch.py | 16 +++++++++------- 2 files changed, 19 insertions(+), 9 deletions(-) diff --git a/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml b/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml index 33addb108d..bde1b024d7 100644 --- a/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml +++ b/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml @@ -11,13 +11,21 @@ max_x: 100.0 min_y: -50.0 max_y: 50.0 + max_z: 10.7 # recommended 2.5 for non elevation_grid_mode + min_z: -8.7 # recommended 0.0 for non elevation_grid_mode negative: False common_ground_filter: plugin: "ground_segmentation::ScanGroundFilterComponent" parameters: global_slope_max_angle_deg: 10.0 - local_slope_max_angle_deg: 30.0 + local_slope_max_angle_deg: 13.0 # recommended 30.0 for non elevation_grid_mode split_points_distance_tolerance: 0.2 + use_virtual_ground_point: True split_height_distance: 0.2 - use_virtual_ground_point: False + non_ground_height_threshold: 0.20 + grid_size_m: 0.1 + grid_mode_switch_radius: 20.0 + gnd_grid_buffer_size: 4 + detection_range_z_max: 2.5 + elevation_grid_mode: true diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 520892e3dc..f5961785c4 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -85,8 +85,6 @@ def create_additional_pipeline(self, lidar_name): { "input_frame": LaunchConfiguration("base_frame"), "output_frame": LaunchConfiguration("base_frame"), - "min_z": self.vehicle_info["min_height_offset"], - "max_z": self.vehicle_info["max_height_offset"], }, self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"], ], @@ -219,8 +217,6 @@ def create_common_pipeline(self, input_topic, output_topic): { "input_frame": LaunchConfiguration("base_frame"), "output_frame": LaunchConfiguration("base_frame"), - "min_z": self.vehicle_info["min_height_offset"], - "max_z": self.vehicle_info["max_height_offset"], }, self.ground_segmentation_param["common_crop_box_filter"]["parameters"], ], @@ -239,7 +235,12 @@ def create_common_pipeline(self, input_topic, output_topic): ("input", "range_cropped/pointcloud"), ("output", output_topic), ], - parameters=[self.ground_segmentation_param["common_ground_filter"]["parameters"]], + parameters=[ + self.ground_segmentation_param["common_ground_filter"]["parameters"], + self.vehicle_info, + {"input_frame": "base_link"}, + {"output_frame": "base_link"}, + ], extra_arguments=[ {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} ], @@ -268,7 +269,7 @@ def create_single_frame_obstacle_segmentation_components(self, input_topic, outp components.append( self.get_additional_lidars_concatenated_component( input_topics=[common_pipeline_output] - + [f"{x}/pointcloud" for x in additional_lidars], + + list(map(lambda x: f"{x}/pointcloud"), additional_lidars), output_topic=relay_topic if use_ransac else output_topic, ) ) @@ -476,6 +477,7 @@ def launch_setup(context, *args, **kwargs): output_topic=relay_topic if pipeline.use_time_series_filter else pipeline.output_topic, + context=context, ) ) if pipeline.use_time_series_filter: @@ -516,7 +518,7 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("use_intra_process", "True") add_launch_arg("use_pointcloud_container", "False") add_launch_arg("container_name", "perception_pipeline_container") - add_launch_arg("input/pointcloud", "sensing/lidar/concatenated/pointcloud") + add_launch_arg("input/pointcloud", "/sensing/lidar/concatenated/pointcloud") set_container_executable = SetLaunchConfiguration( "container_executable", From 3bfdaa1b2d9d5b22d3ee1d88a09941276405185e Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Mon, 17 Oct 2022 16:50:34 +0900 Subject: [PATCH 644/851] fix: longitudinal_controller_mode arg (#516) * fix: longitudinal_controller_mode arg Signed-off-by: Shumpei Wakabayashi * feat: add longitudinal controller arg Signed-off-by: Shumpei Wakabayashi Signed-off-by: Shumpei Wakabayashi --- autoware_launch/launch/planning_simulator.launch.xml | 2 ++ control_launch/launch/control.launch.py | 1 + 2 files changed, 3 insertions(+) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 6b099fa824..d6fb815672 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -63,6 +63,8 @@ + + diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 1d84fc6b31..2878f58b89 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -80,6 +80,7 @@ def launch_setup(context, *args, **kwargs): { "ctrl_period": 0.03, "lateral_controller_mode": LaunchConfiguration("lateral_controller_mode"), + "longitudinal_controller_mode": LaunchConfiguration("longitudinal_controller_mode"), }, nearest_search_param, lon_controller_param, From 516a20d25e670f0c390d6ad5826b1dfeb9d2fb78 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Tue, 18 Oct 2022 09:17:55 +0900 Subject: [PATCH 645/851] feat(planning_launch): add turn signal parameter (#517) Signed-off-by: yutaka Signed-off-by: yutaka --- .../behavior_path_planner.param.yaml | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index 55b531e997..b9c50b15e5 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -15,7 +15,13 @@ drivable_area_margin: 6.0 refine_goal_search_radius_range: 7.5 - intersection_search_distance: 30.0 + + # parameters for turn signal decider + turn_signal_intersection_search_distance: 30.0 + turn_signal_intersection_angle_threshold_deg: 15.0 + turn_signal_minimum_search_distance: 10.0 + turn_signal_search_time: 3.0 + turn_signal_shift_length_threshold: 0.3 path_interval: 2.0 From 7f480a8a47d24f7aa286ce2c5389272789300f88 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 18 Oct 2022 22:22:43 +0900 Subject: [PATCH 646/851] feat(freespace_planner): use vehicle_info (#521) Signed-off-by: Takamasa Horibe Signed-off-by: Takamasa Horibe --- .../parking/freespace_planner/freespace_planner.param.yaml | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml b/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml index d6152c4f56..d2226091b5 100644 --- a/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml +++ b/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: # -- Node Configurations -- - planning_algorithm: "astar" + planning_algorithm: "astar" # options: astar, rrtstar waypoints_velocity: 5.0 update_rate: 10.0 th_arrived_distance_m: 1.0 @@ -15,10 +15,6 @@ # -- Configurations common to the all planners -- # base configs time_limit: 30000.0 - # robot configs # TODO replace by vehicle_info - robot_length: 4.5 - robot_width: 1.75 - robot_base2back: 1.0 minimum_turning_radius: 9.0 maximum_turning_radius: 9.0 turning_radius_size: 1 From 828e49150c58a90ad272c2269b91273921237382 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 11 Oct 2022 12:24:07 +0900 Subject: [PATCH 647/851] feat(behavior_path_planner): pull_over lateral goal search (#507) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_over/pull_over.param.yaml | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index 281d91f574..8e277959bc 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -16,9 +16,12 @@ forward_goal_search_length: 20.0 backward_goal_search_length: 20.0 goal_search_interval: 2.0 - goal_to_obstacle_margin: 3.0 + longitudinal_margin: 3.0 + max_lateral_offset: 1.0 + lateral_offset_interval: 0.25 # occupancy grid map use_occupancy_grid: true + use_occupancy_grid_for_longitudinal_margin: false occupancy_grid_collision_check_margin: 0.0 theta_size: 360 obstacle_threshold: 60 From b9815a46484230d49b94633fdb43be8617c8a8b1 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Thu, 13 Oct 2022 15:46:37 +0900 Subject: [PATCH 648/851] feat(control_launch): add longitudinal controller option (#514) * feat(control_launch): add longitudinal controller option Signed-off-by: tanaka3 * ci(pre-commit): autofix Signed-off-by: tanaka3 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- control_launch/launch/control.launch.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 13e5a7dd51..42258383c7 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -262,6 +262,13 @@ def add_launch_arg(name: str, default_value=None, description=None): "lateral controller mode: `mpc_follower` or `pure_pursuit`", ) + # longitudinal controller mode + add_launch_arg( + "longitudinal_controller_mode", + "pid", + "longitudinal controller mode: `pid`", + ) + # parameter file path add_launch_arg( "nearest_search_param_path", From 74d18086ce260fa5bc1848dac0f486c66540d269 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 14 Oct 2022 09:27:44 +0900 Subject: [PATCH 649/851] feat(localization_launch): sync with awf/universe (add twist2accel, add group tag) (#515) --- .../pose_twist_fusion_filter.launch.xml | 58 +++++++++++-------- 1 file changed, 35 insertions(+), 23 deletions(-) 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 9988df4cef..3c109769e1 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,28 +1,40 @@ - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - - - - + + + + + + + + - - - - - - - - - + + + + + + + + From 7bce29c5b23ce462d6e5afaab12f45a0c39206af Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Fri, 14 Oct 2022 22:56:23 +0900 Subject: [PATCH 650/851] fix(ground_segmentation): add param for grid scan_ground_filter (#509) * fix: add param for grid scan_ground_filter Signed-off-by: badai-nguyen * chore: unify parameters as universe launch Signed-off-by: badai-nguyen * fix search package name Signed-off-by: Shunsuke Miura Signed-off-by: badai-nguyen Signed-off-by: Shunsuke Miura Co-authored-by: Shunsuke Miura Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --- .../ground_segmentation.param.yaml | 12 ++++++++++-- .../ground_segmentation.launch.py | 16 +++++++++------- 2 files changed, 19 insertions(+), 9 deletions(-) diff --git a/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml b/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml index 33addb108d..bde1b024d7 100644 --- a/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml +++ b/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml @@ -11,13 +11,21 @@ max_x: 100.0 min_y: -50.0 max_y: 50.0 + max_z: 10.7 # recommended 2.5 for non elevation_grid_mode + min_z: -8.7 # recommended 0.0 for non elevation_grid_mode negative: False common_ground_filter: plugin: "ground_segmentation::ScanGroundFilterComponent" parameters: global_slope_max_angle_deg: 10.0 - local_slope_max_angle_deg: 30.0 + local_slope_max_angle_deg: 13.0 # recommended 30.0 for non elevation_grid_mode split_points_distance_tolerance: 0.2 + use_virtual_ground_point: True split_height_distance: 0.2 - use_virtual_ground_point: False + non_ground_height_threshold: 0.20 + grid_size_m: 0.1 + grid_mode_switch_radius: 20.0 + gnd_grid_buffer_size: 4 + detection_range_z_max: 2.5 + elevation_grid_mode: true diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 520892e3dc..f5961785c4 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -85,8 +85,6 @@ def create_additional_pipeline(self, lidar_name): { "input_frame": LaunchConfiguration("base_frame"), "output_frame": LaunchConfiguration("base_frame"), - "min_z": self.vehicle_info["min_height_offset"], - "max_z": self.vehicle_info["max_height_offset"], }, self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"], ], @@ -219,8 +217,6 @@ def create_common_pipeline(self, input_topic, output_topic): { "input_frame": LaunchConfiguration("base_frame"), "output_frame": LaunchConfiguration("base_frame"), - "min_z": self.vehicle_info["min_height_offset"], - "max_z": self.vehicle_info["max_height_offset"], }, self.ground_segmentation_param["common_crop_box_filter"]["parameters"], ], @@ -239,7 +235,12 @@ def create_common_pipeline(self, input_topic, output_topic): ("input", "range_cropped/pointcloud"), ("output", output_topic), ], - parameters=[self.ground_segmentation_param["common_ground_filter"]["parameters"]], + parameters=[ + self.ground_segmentation_param["common_ground_filter"]["parameters"], + self.vehicle_info, + {"input_frame": "base_link"}, + {"output_frame": "base_link"}, + ], extra_arguments=[ {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} ], @@ -268,7 +269,7 @@ def create_single_frame_obstacle_segmentation_components(self, input_topic, outp components.append( self.get_additional_lidars_concatenated_component( input_topics=[common_pipeline_output] - + [f"{x}/pointcloud" for x in additional_lidars], + + list(map(lambda x: f"{x}/pointcloud"), additional_lidars), output_topic=relay_topic if use_ransac else output_topic, ) ) @@ -476,6 +477,7 @@ def launch_setup(context, *args, **kwargs): output_topic=relay_topic if pipeline.use_time_series_filter else pipeline.output_topic, + context=context, ) ) if pipeline.use_time_series_filter: @@ -516,7 +518,7 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("use_intra_process", "True") add_launch_arg("use_pointcloud_container", "False") add_launch_arg("container_name", "perception_pipeline_container") - add_launch_arg("input/pointcloud", "sensing/lidar/concatenated/pointcloud") + add_launch_arg("input/pointcloud", "/sensing/lidar/concatenated/pointcloud") set_container_executable = SetLaunchConfiguration( "container_executable", From 3b963427f3fb20c09e99ab5ffc52c75d7276872f Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Mon, 17 Oct 2022 16:50:34 +0900 Subject: [PATCH 651/851] fix: longitudinal_controller_mode arg (#516) * fix: longitudinal_controller_mode arg Signed-off-by: Shumpei Wakabayashi * feat: add longitudinal controller arg Signed-off-by: Shumpei Wakabayashi Signed-off-by: Shumpei Wakabayashi --- autoware_launch/launch/planning_simulator.launch.xml | 2 ++ control_launch/launch/control.launch.py | 1 + 2 files changed, 3 insertions(+) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 6b099fa824..d6fb815672 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -63,6 +63,8 @@ + + diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 42258383c7..facfa188f7 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -80,6 +80,7 @@ def launch_setup(context, *args, **kwargs): { "ctrl_period": 0.03, "lateral_controller_mode": LaunchConfiguration("lateral_controller_mode"), + "longitudinal_controller_mode": LaunchConfiguration("longitudinal_controller_mode"), }, nearest_search_param, lon_controller_param, From 245dcd4be3843fb6cbd387d8f60558382043fa8c Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Tue, 18 Oct 2022 09:17:55 +0900 Subject: [PATCH 652/851] feat(planning_launch): add turn signal parameter (#517) Signed-off-by: yutaka Signed-off-by: yutaka --- .../behavior_path_planner.param.yaml | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index 55b531e997..b9c50b15e5 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -15,7 +15,13 @@ drivable_area_margin: 6.0 refine_goal_search_radius_range: 7.5 - intersection_search_distance: 30.0 + + # parameters for turn signal decider + turn_signal_intersection_search_distance: 30.0 + turn_signal_intersection_angle_threshold_deg: 15.0 + turn_signal_minimum_search_distance: 10.0 + turn_signal_search_time: 3.0 + turn_signal_shift_length_threshold: 0.3 path_interval: 2.0 From 54b9642db21f03ea19f8ddea5e69a7f9a6f5136f Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 18 Oct 2022 22:22:43 +0900 Subject: [PATCH 653/851] feat(freespace_planner): use vehicle_info (#521) Signed-off-by: Takamasa Horibe Signed-off-by: Takamasa Horibe --- .../parking/freespace_planner/freespace_planner.param.yaml | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml b/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml index d6152c4f56..d2226091b5 100644 --- a/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml +++ b/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: # -- Node Configurations -- - planning_algorithm: "astar" + planning_algorithm: "astar" # options: astar, rrtstar waypoints_velocity: 5.0 update_rate: 10.0 th_arrived_distance_m: 1.0 @@ -15,10 +15,6 @@ # -- Configurations common to the all planners -- # base configs time_limit: 30000.0 - # robot configs # TODO replace by vehicle_info - robot_length: 4.5 - robot_width: 1.75 - robot_base2back: 1.0 minimum_turning_radius: 9.0 maximum_turning_radius: 9.0 turning_radius_size: 1 From 096043bd75012010c83d02565bc2da284f781e58 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 19 Oct 2022 16:09:33 +0900 Subject: [PATCH 654/851] feat: sync routing api (#520) Signed-off-by: Takagi, Isamu Signed-off-by: Takagi, Isamu --- .../mission_planning.launch.py | 73 ------------------- .../mission_planning.launch.xml | 10 ++- planning_launch/launch/planning.launch.xml | 3 +- 3 files changed, 7 insertions(+), 79 deletions(-) delete mode 100644 planning_launch/launch/mission_planning/mission_planning.launch.py diff --git a/planning_launch/launch/mission_planning/mission_planning.launch.py b/planning_launch/launch/mission_planning/mission_planning.launch.py deleted file mode 100644 index cc3952f93b..0000000000 --- a/planning_launch/launch/mission_planning/mission_planning.launch.py +++ /dev/null @@ -1,73 +0,0 @@ -# Copyright 2021 Tier IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -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(): - container = ComposableNodeContainer( - name="mission_planning_container", - namespace="", - package="rclcpp_components", - executable="component_container", - composable_node_descriptions=[ - ComposableNode( - package="mission_planner", - plugin="mission_planner::MissionPlannerLanelet2", - name="mission_planner", - remappings=[ - ("input/vector_map", "/map/vector_map"), - ("input/goal_pose", "/planning/mission_planning/goal"), - ("input/checkpoint", "/planning/mission_planning/checkpoint"), - ("output/route", "/planning/mission_planning/route"), - ("debug/route_marker", "/planning/mission_planning/route_marker"), - ], - parameters=[ - { - "map_frame": "map", - "base_link_frame": "base_link", - } - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ), - ComposableNode( - package="mission_planner", - plugin="mission_planner::GoalPoseVisualizer", - name="goal_pose_visualizer", - remappings=[ - ("input/route", "/planning/mission_planning/route"), - ("output/goal_pose", "/planning/mission_planning/echo_back_goal_pose"), - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ), - ], - ) - return launch.LaunchDescription( - [ - DeclareLaunchArgument( - "use_intra_process", - default_value="false", - description="use ROS2 component container communication", - ), - container, - ] - ) diff --git a/planning_launch/launch/mission_planning/mission_planning.launch.xml b/planning_launch/launch/mission_planning/mission_planning.launch.xml index 712840021b..c1ace97b97 100644 --- a/planning_launch/launch/mission_planning/mission_planning.launch.xml +++ b/planning_launch/launch/mission_planning/mission_planning.launch.xml @@ -1,7 +1,9 @@ - - + + + - - + + + diff --git a/planning_launch/launch/planning.launch.xml b/planning_launch/launch/planning.launch.xml index f6a7abec76..6e117d6616 100644 --- a/planning_launch/launch/planning.launch.xml +++ b/planning_launch/launch/planning.launch.xml @@ -10,8 +10,7 @@ - - + From d4e44cc8a0bb48a0ccb239c10f875fa491281d3d Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Thu, 20 Oct 2022 18:07:23 +0900 Subject: [PATCH 655/851] refactor(autoware.rviz): unify virtual wall marker name (#518) --- 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 ce17aef92d..c2282509ca 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1442,7 +1442,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/wall_marker + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/virtual_wall Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true @@ -1484,7 +1484,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/cruise_wall_marker + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/cruise/virtual_wall Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true From 65617171508c2b56b8dd82127b7428ea04421103 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Fri, 21 Oct 2022 14:33:49 +0900 Subject: [PATCH 656/851] feat(multi_object_tracking): enable delay compensation (#413) Signed-off-by: Yukihiro Saito Signed-off-by: Yukihiro Saito --- .../launch/object_recognition/tracking/tracking.launch.xml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml index aac0e32289..65ac62ef3b 100644 --- a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml +++ b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml @@ -1,8 +1,13 @@ + + + + + From fc33ada3b252bbca1708b285e2ae58af2cbc3368 Mon Sep 17 00:00:00 2001 From: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Date: Fri, 21 Oct 2022 23:38:07 +0900 Subject: [PATCH 657/851] fix(ground_segmentation): fix ground segmentation launcher (#524) Signed-off-by: Shunsuke Miura Signed-off-by: Shunsuke Miura --- .../ground_segmentation/ground_segmentation.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index f5961785c4..f63af31655 100644 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -269,7 +269,7 @@ def create_single_frame_obstacle_segmentation_components(self, input_topic, outp components.append( self.get_additional_lidars_concatenated_component( input_topics=[common_pipeline_output] - + list(map(lambda x: f"{x}/pointcloud"), additional_lidars), + + [f"{x}/pointcloud" for x in additional_lidars], output_topic=relay_topic if use_ransac else output_topic, ) ) From b0b7ff48292cf2d298d6a5bedb84f13c216bd348 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 24 Oct 2022 16:56:00 +0900 Subject: [PATCH 658/851] chore: change control launch (#527) * fix: fix param file name Signed-off-by: tomoya.kimura * feat: remove unused parameter Signed-off-by: tomoya.kimura Signed-off-by: tomoya.kimura --- control_launch/launch/control.launch.py | 2 +- control_launch/launch/control.launch.xml | 2 -- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 2878f58b89..d58be09a25 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -319,7 +319,7 @@ def add_launch_arg(name: str, default_value=None, description=None): "shift_decider_param_path", [ FindPackageShare("control_launch"), - "/config/shift_decider/shift_decider_param.param.yaml", + "/config/shift_decider/shift_decider.param.yaml", ], "path to the parameter file of shift_decider", ) diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index 54ceac8262..db899b4573 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -3,7 +3,6 @@ - @@ -12,7 +11,6 @@ - From 2b2cfa744367d96229c8bc063fd1e8375f6c53ee Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 25 Oct 2022 11:26:36 +0900 Subject: [PATCH 659/851] feat(behavior_path_planner): add parameters to expand the drivable area (#502) Signed-off-by: Maxime CLEMENT --- .../drivable_area_expansion.param.yaml | 20 +++++++++++++++++++ .../lane_following/lane_following.param.yaml | 3 --- .../behavior_planning.launch.py | 13 ++++++++++++ .../behavior_planning.launch.xml | 1 + 4 files changed, 34 insertions(+), 3 deletions(-) create mode 100644 planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml new file mode 100644 index 0000000000..660a4d2af0 --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml @@ -0,0 +1,20 @@ +/**: + ros__parameters: + avoidance: + drivable_area_right_bound_offset: 0.0 + drivable_area_left_bound_offset: 0.0 + lane_change: + drivable_area_right_bound_offset: 0.0 + drivable_area_left_bound_offset: 0.0 + lane_following: + drivable_area_right_bound_offset: 0.0 + drivable_area_left_bound_offset: 0.0 + pull_out: + drivable_area_right_bound_offset: 0.0 + drivable_area_left_bound_offset: 0.0 + pull_over: + drivable_area_right_bound_offset: 0.0 + drivable_area_left_bound_offset: 0.0 + side_shift: + drivable_area_right_bound_offset: 0.0 + drivable_area_left_bound_offset: 0.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml index f685f8a657..b6a9574bb4 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml @@ -1,7 +1,4 @@ /**: ros__parameters: lane_following: - expand_drivable_area: false - right_bound_offset: 0.5 - left_bound_offset: 0.5 lane_change_prepare_duration: 2.0 diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index f3955b1aab..3b831d7080 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -120,6 +120,18 @@ def generate_launch_description(): with open(pull_out_param_path, "r") as f: pull_out_param = yaml.safe_load(f)["/**"]["ros__parameters"] + drivable_area_expansion_param_path = os.path.join( + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_path_planner", + "drivable_area_expansion.param.yaml", + ) + with open(drivable_area_expansion_param_path, "r") as f: + drivable_area_expansion_param = yaml.safe_load(f)["/**"]["ros__parameters"] + behavior_path_planner_param_path = os.path.join( get_package_share_directory("planning_launch"), "config", @@ -156,6 +168,7 @@ def generate_launch_description(): lane_following_param, pull_over_param, pull_out_param, + drivable_area_expansion_param, behavior_path_planner_param, { "bt_tree_config_path": [ 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 a16b2f56cb..ddd7e8b894 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 @@ -15,6 +15,7 @@ + From d953e7c3899fa1d68b2fd57c3c64e364f30d7afd Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 25 Oct 2022 15:36:18 +0900 Subject: [PATCH 660/851] feat(motion_velocity_smoother): change max_lateral_accel from 0.8 to 1.0 (#512) Signed-off-by: Maxime CLEMENT --- .../motion_velocity_smoother.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index 016d313e9b..4a47cc89e2 100644 --- a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -8,7 +8,7 @@ margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m] # curve parameters - max_lateral_accel: 0.8 # max lateral acceleration limit [m/ss] + max_lateral_accel: 1.0 # 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 From 5e0e4be30056dd9a407cf35dbfaee6eed66b7057 Mon Sep 17 00:00:00 2001 From: yabuta Date: Wed, 26 Oct 2022 15:08:51 +0900 Subject: [PATCH 661/851] feat(autoware_api/rosbridge): add rosbridge max message size parameter (#522) * add param * change parameter value * delete from root launcher * delete space --- autoware_api_launch/launch/autoware_api.launch.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/autoware_api_launch/launch/autoware_api.launch.xml b/autoware_api_launch/launch/autoware_api.launch.xml index 45c1f62d12..509e0c4f9c 100644 --- a/autoware_api_launch/launch/autoware_api.launch.xml +++ b/autoware_api_launch/launch/autoware_api.launch.xml @@ -2,6 +2,7 @@ + @@ -31,6 +32,7 @@ + From 436d30c2058757bf6d93d37a1647774484c99be6 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 27 Oct 2022 12:19:09 +0900 Subject: [PATCH 662/851] feat(planning_launch): update smoother resampling parameter (#530) Signed-off-by: yutaka Signed-off-by: yutaka --- .../motion_velocity_smoother.param.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index 016d313e9b..d95c9992c8 100644 --- a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -32,8 +32,8 @@ # resampling parameters for optimization max_trajectory_length: 200.0 # max trajectory length for resampling [m] min_trajectory_length: 150.0 # min trajectory length for resampling [m] - resample_time: 5.0 # resample total time for dense sampling [s] - dense_resample_dt: 0.1 # resample time interval for dense sampling [s] + resample_time: 2.0 # resample total time for dense sampling [s] + dense_resample_dt: 0.2 # resample time interval for dense sampling [s] dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m] sparse_resample_dt: 0.5 # resample time interval for sparse sampling [s] sparse_min_interval_distance: 4.0 # minimum points-interval length for sparse sampling [m] From bc07407dbcb8bf0bcd9e6d1bdc17ce313ad14fa7 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Fri, 28 Oct 2022 10:29:42 +0900 Subject: [PATCH 663/851] fix: fix xacro command in vehicle.launch (#535) Signed-off-by: tomoya.kimura Signed-off-by: tomoya.kimura --- vehicle_launch/launch/vehicle_description.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/vehicle_launch/launch/vehicle_description.launch.xml b/vehicle_launch/launch/vehicle_description.launch.xml index 3feda41d8c..5a2bd35382 100644 --- a/vehicle_launch/launch/vehicle_description.launch.xml +++ b/vehicle_launch/launch/vehicle_description.launch.xml @@ -9,7 +9,7 @@ - + From c04cc17401eced009290588e294c5dbc71f7c247 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Mon, 7 Nov 2022 17:00:17 +0900 Subject: [PATCH 664/851] feat: delete integration_launch (#537) --- integration_launch/CMakeLists.txt | 16 -- integration_launch/README.md | 14 -- .../integration_launch.drawio.svg | 228 ------------------ .../launch/ci_planning_simulator.launch.xml | 31 --- integration_launch/launch/release.launch.xml | 19 -- integration_launch/package.xml | 30 --- 6 files changed, 338 deletions(-) delete mode 100644 integration_launch/CMakeLists.txt delete mode 100644 integration_launch/README.md delete mode 100644 integration_launch/integration_launch.drawio.svg delete mode 100644 integration_launch/launch/ci_planning_simulator.launch.xml delete mode 100644 integration_launch/launch/release.launch.xml delete mode 100644 integration_launch/package.xml diff --git a/integration_launch/CMakeLists.txt b/integration_launch/CMakeLists.txt deleted file mode 100644 index c3ddc04a7d..0000000000 --- a/integration_launch/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ - -cmake_minimum_required(VERSION 3.5) -project(integration_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/integration_launch/README.md b/integration_launch/README.md deleted file mode 100644 index 4a58b1b467..0000000000 --- a/integration_launch/README.md +++ /dev/null @@ -1,14 +0,0 @@ -# integration_launch - -## Structure - -![integration_launch](./integration_launch.drawio.svg) - -## Package Dependencies - -- autoware_launch -- scenario_runner - -## Notes - -This package is only used for continuous integration. diff --git a/integration_launch/integration_launch.drawio.svg b/integration_launch/integration_launch.drawio.svg deleted file mode 100644 index f40a0b345c..0000000000 --- a/integration_launch/integration_launch.drawio.svg +++ /dev/null @@ -1,228 +0,0 @@ - - - - - - - -
    -
    -
    - ci_planning_simulator.launch.xml -
    -
    -
    - - package: integration_launch - -
    -
    -
    -
    -
    - - ci_planning_simulator.launch.xml... - -
    -
    - - - - -
    -
    -
    - launch name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - launch name... - -
    -
    - - - - -
    -
    -
    - ex: -
    -
    -
    -
    - - ex: - -
    -
    - - - - -
    -
    -
    - node name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - node name... - -
    -
    - - - - -
    -
    -
    - planning_simulator.launch.xml -
    -
    -
    - - package: autoware_launch - -
    -
    -
    -
    -
    - - planning_simulator.launch.xml... - -
    -
    - - - - -
    -
    -
    - other name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - other name... - -
    -
    - - - - - - -
    -
    -
    - scenario_runner.launch.xml -
    -
    -
    - - package: scenario_runner - -
    -
    -
    -
    -
    - - scenario_runner.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - release.launch.xml -
    -
    -
    - - package: integration_launch - -
    -
    -
    -
    -
    - - release.launch.xml... - -
    -
    - - - - -
    -
    -
    - autoware.launch.xml -
    -
    -
    - - package: autoware_launch - -
    -
    -
    -
    -
    - - autoware.launch.xml... - -
    -
    - - -
    - - - - - Viewer does not support full SVG 1.1 - - - -
    \ No newline at end of file diff --git a/integration_launch/launch/ci_planning_simulator.launch.xml b/integration_launch/launch/ci_planning_simulator.launch.xml deleted file mode 100644 index 04ea5f3b73..0000000000 --- a/integration_launch/launch/ci_planning_simulator.launch.xml +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/integration_launch/launch/release.launch.xml b/integration_launch/launch/release.launch.xml deleted file mode 100644 index 3a27a1fa20..0000000000 --- a/integration_launch/launch/release.launch.xml +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/integration_launch/package.xml b/integration_launch/package.xml deleted file mode 100644 index 54d42a8492..0000000000 --- a/integration_launch/package.xml +++ /dev/null @@ -1,30 +0,0 @@ - - - integration_launch - 0.1.0 - The integration_launch package - - Hiroyuki Obinata - Apache 2 - ament_cmake_auto - - control_launch - localization_launch - perception_launch - planning_launch - python3-bson - python3-tornado - rviz2 - system_launch - tier4_map_launch - tier4_sensing_launch - vehicle_launch - web_controller - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - From 0fa1e0074201d349b767f2b2505898d57ea3150d Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Wed, 9 Nov 2022 10:25:39 +0900 Subject: [PATCH 665/851] fix(planning_launch): launch path (#531) Signed-off-by: Shumpei Wakabayashi Signed-off-by: Shumpei Wakabayashi --- .../lane_driving/behavior_planning/behavior_planning.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 3b831d7080..0f00aeb60f 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -467,7 +467,7 @@ def generate_launch_description(): load_vector_map_inside_area_filter = IncludeLaunchDescription( PythonLaunchDescriptionSource( [ - FindPackageShare("tier4_planning_launch"), + FindPackageShare("planning_launch"), "/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py", ] ), From 6b00a8c811c21018e6459d9bb623de3df22936c6 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 9 Nov 2022 15:37:23 +0900 Subject: [PATCH 666/851] refactor(ndt): remove package (#532) Signed-off-by: kminoda Signed-off-by: kminoda --- .../config/ndt_scan_matcher.param.yaml | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/localization_launch/config/ndt_scan_matcher.param.yaml b/localization_launch/config/ndt_scan_matcher.param.yaml index 8e63ed344b..2ace1e86c5 100644 --- a/localization_launch/config/ndt_scan_matcher.param.yaml +++ b/localization_launch/config/ndt_scan_matcher.param.yaml @@ -6,10 +6,6 @@ # 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 @@ -25,7 +21,6 @@ # Converged param type # 0=TRANSFORM_PROBABILITY, 1=NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD - # NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD is only available when NDTImplementType::OMP is selected converged_param_type: 1 # If converged_param_type is 0 @@ -45,12 +40,12 @@ # Tolerance of distance difference between two initial poses used for linear interpolation. [m] initial_pose_distance_tolerance_m: 10.0 - # neighborhood search method in OMP + # neighborhood search method # 0=KDTREE, 1=DIRECT26, 2=DIRECT7, 3=DIRECT1 - omp_neighborhood_search_method: 0 + neighborhood_search_method: 0 # Number of threads used for parallel computing - omp_num_threads: 4 + num_threads: 4 # The covariance of output pose output_pose_covariance: From d3503d3befe6e9a31f008dbf7e415bfce766391f Mon Sep 17 00:00:00 2001 From: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Date: Wed, 9 Nov 2022 20:45:04 +0900 Subject: [PATCH 667/851] Feat/sync perception launch (#534) * sync from autoware.universe Signed-off-by: Shunsuke Miura * sync perception launch Signed-off-by: Shunsuke Miura * Fix package.xml Signed-off-by: Shunsuke Miura * sync from autoware.universe again Signed-off-by: Shunsuke Miura Signed-off-by: Shunsuke Miura --- .../data_association_matrix.param.yaml | 4 +- ...ra_lidar_fusion_based_detection.launch.xml | 64 ++++++++++++++++--- ...ar_radar_fusion_based_detection.launch.xml | 4 ++ .../detection/detection.launch.xml | 7 +- .../lidar_based_detection.launch.xml | 17 ++++- .../lidar_radar_based_detection.launch.xml | 4 ++ ...ntcloud_based_occupancy_grid_map.launch.py | 17 +++-- .../launch/perception.launch.xml | 9 +-- .../traffic_light.launch.xml | 20 ++---- perception_launch/package.xml | 6 +- 10 files changed, 110 insertions(+), 42 deletions(-) diff --git a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml index 1790315ae5..2541ab0367 100644 --- a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml +++ b/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml @@ -22,8 +22,8 @@ 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #BICYCLE 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN max_area_matrix: - # NOTE(yukke42): The size of truck is 12 m length x 3 m width. - # NOTE(yukke42): The size of trailer is 20 m length x 3 m width. + # NOTE: The size of truck is 12 m length x 3 m width. + # NOTE: The size of trailer is 20 m length x 3 m width. #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN [100.00, 100.00, 100.00, 100.00, 100.00, 100.00, 100.00, 100.00, #UNKNOWN 12.10, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #CAR 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 3b6c8388e8..eaf1dc5481 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 @@ -22,9 +22,14 @@ + + + + + - - - - + + + + + + + + + + @@ -169,6 +180,7 @@ +
    @@ -181,6 +193,40 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -205,23 +251,25 @@ - + + + - - + + - + diff --git a/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml index 802694e2ed..86e37f80d4 100644 --- a/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -4,8 +4,10 @@ + + @@ -50,8 +52,10 @@ + + diff --git a/perception_launch/launch/object_recognition/detection/detection.launch.xml b/perception_launch/launch/object_recognition/detection/detection.launch.xml index 1196988f07..c4a9c00e46 100644 --- a/perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -4,8 +4,9 @@ - + + @@ -53,6 +54,7 @@ +
    @@ -81,6 +83,7 @@ +
    @@ -92,6 +95,7 @@ +
    @@ -103,6 +107,7 @@ +
    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 5c9e4e8861..9e772759df 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 @@ -5,9 +5,14 @@ + + + + + @@ -62,6 +67,11 @@ + + + + + @@ -81,6 +91,7 @@ +
    @@ -116,16 +127,18 @@ + + - + - + diff --git a/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml index db1fc26863..8150315c95 100644 --- a/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml @@ -4,8 +4,10 @@ + + @@ -14,8 +16,10 @@ + + diff --git a/perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py b/perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py index 2b7f9f8e83..2feefdfb10 100644 --- a/perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py +++ b/perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py @@ -16,8 +16,6 @@ from launch.actions import DeclareLaunchArgument from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition -from launch.conditions import LaunchConfigurationEquals -from launch.conditions import LaunchConfigurationNotEquals from launch.conditions import UnlessCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer @@ -62,26 +60,27 @@ def add_launch_arg(name: str, default_value=None): ] occupancy_grid_map_container = ComposableNodeContainer( - condition=LaunchConfigurationEquals("container", ""), - name="occupancy_grid_map_container", + name=LaunchConfiguration("container_name"), namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), composable_node_descriptions=composable_nodes, + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), output="screen", ) load_composable_nodes = LoadComposableNodes( - condition=LaunchConfigurationNotEquals("container", ""), composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration("container"), + target_container=LaunchConfiguration("container_name"), + condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), ) return LaunchDescription( [ - add_launch_arg("container", ""), - add_launch_arg("use_multithread", "false"), - add_launch_arg("use_intra_process", "false"), + add_launch_arg("use_multithread", "False"), + add_launch_arg("use_intra_process", "True"), + add_launch_arg("use_pointcloud_container", "False"), + add_launch_arg("container_name", "occupancy_grid_map_container"), add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"), add_launch_arg("input/raw_pointcloud", "concatenated/pointcloud"), add_launch_arg("output", "occupancy_grid"), diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index 858eb56688..91931d53b2 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -2,9 +2,8 @@ - - + @@ -24,6 +23,7 @@ + - @@ -94,6 +93,7 @@ + @@ -101,7 +101,8 @@ - + + 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 6605209150..8d3ca7452b 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -1,22 +1,13 @@ - - - - - + + + + @@ -51,7 +42,6 @@ - - + diff --git a/perception_launch/package.xml b/perception_launch/package.xml index a49fa414d0..b593cacef6 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -4,14 +4,17 @@ perception_launch 0.1.0 The perception_launch package - Yukihiro Saito + Shunsuke Miura Apache License 2.0 ament_cmake_auto compare_map_segmentation crosswalk_traffic_light_estimator + detected_object_feature_remover + detected_object_validation + detection_by_tracker euclidean_cluster ground_segmentation image_projection_based_fusion @@ -24,6 +27,7 @@ occupancy_grid_map_outlier_filter pointcloud_preprocessor pointcloud_to_laserscan + probabilistic_occupancy_grid_map shape_estimation tensorrt_yolo traffic_light_classifier From e282e15d4bddcebec6401ecdc5cf525a71cfff20 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 10 Nov 2022 00:56:31 +0900 Subject: [PATCH 668/851] feat: designate cruise planner type runtime (#539) * feat: designate cruise planner type runtime Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- autoware_launch/launch/autoware.launch.xml | 2 ++ planning_launch/launch/planning.launch.xml | 2 ++ .../scenario_planning/lane_driving.launch.xml | 2 ++ .../motion_planning/motion_planning.launch.py | 25 +++++++++++++------ .../scenario_planning.launch.xml | 2 ++ 5 files changed, 26 insertions(+), 7 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 5f2af36436..5b14dd9849 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -11,6 +11,7 @@ + @@ -82,6 +83,7 @@ + diff --git a/planning_launch/launch/planning.launch.xml b/planning_launch/launch/planning.launch.xml index 6e117d6616..8116564f87 100644 --- a/planning_launch/launch/planning.launch.xml +++ b/planning_launch/launch/planning.launch.xml @@ -4,6 +4,7 @@ + @@ -19,6 +20,7 @@ + diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch.xml b/planning_launch/launch/scenario_planning/lane_driving.launch.xml index e232b7a0af..a762fefa93 100644 --- a/planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving.launch.xml @@ -5,6 +5,7 @@ + @@ -28,6 +29,7 @@ + diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index db68a478cf..e1f27d2b44 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -29,6 +29,19 @@ def generate_launch_description(): + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None, description=None): + launch_arguments.append( + DeclareLaunchArgument(name, default_value=default_value, description=description) + ) + + add_launch_arg( + "cruise_planner_type", + "obstacle_stop_planner", + "cruise_planner: obstacle_stop_planner, obstacle_cruise_planner, none`", + ) + # planning common param path common_param_path = os.path.join( get_package_share_directory("planning_launch"), @@ -237,19 +250,19 @@ def generate_launch_description(): obstacle_stop_planner_loader = LoadComposableNodes( composable_node_descriptions=[obstacle_stop_planner_component], target_container=container, - condition=LaunchConfigurationEquals("cruise_planner", "obstacle_stop_planner"), + condition=LaunchConfigurationEquals("cruise_planner_type", "obstacle_stop_planner"), ) obstacle_cruise_planner_loader = LoadComposableNodes( composable_node_descriptions=[obstacle_cruise_planner_component], target_container=container, - condition=LaunchConfigurationEquals("cruise_planner", "obstacle_cruise_planner"), + condition=LaunchConfigurationEquals("cruise_planner_type", "obstacle_cruise_planner"), ) obstacle_cruise_planner_relay_loader = LoadComposableNodes( composable_node_descriptions=[obstacle_cruise_planner_relay_component], target_container=container, - condition=LaunchConfigurationEquals("cruise_planner", "none"), + condition=LaunchConfigurationEquals("cruise_planner_type", "none"), ) surround_obstacle_checker_loader = LoadComposableNodes( @@ -270,15 +283,13 @@ def generate_launch_description(): ) return launch.LaunchDescription( - [ + launch_arguments + + [ DeclareLaunchArgument( "input_path_topic", default_value="/planning/scenario_planning/lane_driving/behavior_planning/path", ), DeclareLaunchArgument("use_surround_obstacle_check", default_value="true"), - DeclareLaunchArgument( - "cruise_planner", default_value="obstacle_stop_planner" - ), # select from "obstacle_stop_planner", "obstacle_cruise_planner", "none" DeclareLaunchArgument("use_intra_process", default_value="false"), DeclareLaunchArgument("use_multithread", default_value="false"), set_container_executable, diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index f56685a7cc..fc06076d5a 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -6,6 +6,7 @@ + @@ -47,6 +48,7 @@ + From 9138027097b19408d0805abdea55bf9909125283 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Thu, 10 Nov 2022 16:30:36 +0900 Subject: [PATCH 669/851] fix(ground segmentation): change crop box param (#543) Signed-off-by: badai-nguyen Signed-off-by: badai-nguyen --- .../ground_segmentation/ground_segmentation.param.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml b/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml index bde1b024d7..8d56e12244 100644 --- a/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml +++ b/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml @@ -11,8 +11,8 @@ max_x: 100.0 min_y: -50.0 max_y: 50.0 - max_z: 10.7 # recommended 2.5 for non elevation_grid_mode - min_z: -8.7 # recommended 0.0 for non elevation_grid_mode + max_z: 2.5 # recommended 2.5 for non elevation_grid_mode + min_z: -2.5 # recommended 0.0 for non elevation_grid_mode negative: False common_ground_filter: From 49706698ad82bd83367341df7034815c15fddd8a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 10 Nov 2022 16:40:26 +0900 Subject: [PATCH 670/851] ci(autoware_launch): add a new workflow to update sync-param-files.yaml automatically (#544) * ci(autoware_launch): add a new workflow to update sync-param-files.yaml automatically Signed-off-by: Takayuki Murooka * sync files Signed-off-by: Takayuki Murooka Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .github/sync-files.yaml | 5 ++ .github/update-sync-param-files.py | 80 +++++++++++++++++++ .../workflows/update-sync-param-files.yaml | 54 +++++++++++++ 3 files changed, 139 insertions(+) create mode 100644 .github/update-sync-param-files.py create mode 100644 .github/workflows/update-sync-param-files.yaml diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 2c91ce5316..dad19011ef 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -21,3 +21,8 @@ - source: .github/workflows/build-and-test.yaml - source: .github/workflows/build-and-test-differential.yaml - source: .github/workflows/cancel-previous-workflows.yaml + +- repository: autowarefoundation/autoware_launch + files: + - source: .github/update-sync-param-files.py + - source: .github/workflows/update-sync-param-files.yaml diff --git a/.github/update-sync-param-files.py b/.github/update-sync-param-files.py new file mode 100644 index 0000000000..707909cdd1 --- /dev/null +++ b/.github/update-sync-param-files.py @@ -0,0 +1,80 @@ +import argparse +import dataclasses +from pathlib import Path +from typing import List +from typing import Optional + +import git + +""" +This module updates `sync-param-files.yaml` based on the launch parameter files in `autoware.universe`. +""" + +REPO_NAME = "autowarefoundation/autoware.universe" +REPO_URL = f"https://github.com/{REPO_NAME}.git" +CLONE_PATH = Path("/tmp/autoware.universe") + + +@dataclasses.dataclass +class FileSyncConfig: + source: str + dest: str + replace: Optional[bool] = None + delete_orphaned: Optional[bool] = None + pre_commands: Optional[str] = None + post_commands: Optional[str] = None + + +def create_tier4_launch_sync_configs(tier4_launch_package_path: Path) -> List[FileSyncConfig]: + launch_package_name = tier4_launch_package_path.name + launch_config_path = tier4_launch_package_path / "config" + + sync_configs = [] + for param_file_path in tier4_launch_package_path.glob("config/**/*.param.yaml"): + relative_param_file_path = param_file_path.relative_to(launch_config_path) + + source = param_file_path.relative_to(CLONE_PATH) + dest = Path("autoware_launch/config") / launch_package_name / relative_param_file_path + + sync_configs.append(FileSyncConfig(str(source), str(dest))) + + return sync_configs + + +def dump_sync_config(section_name: str, sync_configs: List[FileSyncConfig]) -> List[str]: + indent = 4 * " " + lines = [f"{indent}# {section_name}\n"] + for sync_config in sync_configs: + lines.append(f"{indent}- source: {sync_config.source}\n") + lines.append(f"{indent} dest: {sync_config.dest}\n") + lines.append("\n") + return lines + + +def main(): + parser = argparse.ArgumentParser() + parser.add_argument("sync_param_files_path", type=Path, help="path to sync-param-files.yaml") + args = parser.parse_args() + + # Clone Autoware + if not CLONE_PATH.exists(): + git.Repo.clone_from(REPO_URL, CLONE_PATH) + + # Create sync config for tier4_*_launch + tier4_launch_package_paths = sorted( + CLONE_PATH.glob("launch/tier4_*_launch"), key=lambda p: p.name + ) + tier4_launch_sync_configs_map = { + p.name: create_tier4_launch_sync_configs(p) for p in tier4_launch_package_paths + } + + # Create sync-param-files.yaml + with open(args.sync_param_files_path, "w") as f: + f.write(f"- repository: {REPO_NAME}\n") + f.write(" files:\n") + for section_name, sync_config in tier4_launch_sync_configs_map.items(): + f.writelines(dump_sync_config(section_name, sync_config)) + + +if __name__ == "__main__": + main() diff --git a/.github/workflows/update-sync-param-files.yaml b/.github/workflows/update-sync-param-files.yaml new file mode 100644 index 0000000000..fbce54b07f --- /dev/null +++ b/.github/workflows/update-sync-param-files.yaml @@ -0,0 +1,54 @@ +name: update-sync-param-files + +on: + schedule: + - cron: 0 0 * * * + workflow_dispatch: + +jobs: + update-sync-param-files: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Check out repository + uses: actions/checkout@v3 + + - name: Install GitPython + run: | + pip3 install GitPython + shell: bash + + - name: Generate sync-param-files.yaml + run: | + python3 .github/update-sync-param-files.py .github/sync-param-files.yaml + + - name: Create PR + id: create-pr + uses: peter-evans/create-pull-request@v4 + with: + token: ${{ steps.generate-token.outputs.token }} + base: ${{ github.event.repository.default_branch }} + branch: update-sync-param-files + title: "chore: update sync-param-files.yaml" + commit-message: "chore: update sync-param-files.yaml" + body: ${{ steps.create-pr-body.outputs.body }} + + - name: Check outputs + run: | + echo "Pull Request Number - ${{ steps.create-pr.outputs.pull-request-number }}" + echo "Pull Request URL - ${{ steps.create-pr.outputs.pull-request-url }}" + shell: bash + + - name: Enable auto-merge + if: ${{ steps.create-pr.outputs.pull-request-operation == 'created' }} + uses: peter-evans/enable-pull-request-automerge@v2 + with: + token: ${{ steps.generate-token.outputs.token }} + pull-request-number: ${{ steps.create-pr.outputs.pull-request-number }} + merge-method: squash From 4252a29fd182b4c62919ea452b93f72735b287bb Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 10 Nov 2022 17:32:23 +0900 Subject: [PATCH 671/851] ci(autoware_launch): sync awf/autoware_launch launch packages to here (#546) * ci(autoware_launch): sync awf/autoware_launch launch packages to here Signed-off-by: kminoda * treat the sync as an individual one Signed-off-by: kminoda Signed-off-by: kminoda --- .github/sync-launch-files.yaml | 13 +++++++++ .github/workflows/sync-launch-files.yaml | 34 ++++++++++++++++++++++++ 2 files changed, 47 insertions(+) create mode 100644 .github/sync-launch-files.yaml create mode 100644 .github/workflows/sync-launch-files.yaml diff --git a/.github/sync-launch-files.yaml b/.github/sync-launch-files.yaml new file mode 100644 index 0000000000..861381e272 --- /dev/null +++ b/.github/sync-launch-files.yaml @@ -0,0 +1,13 @@ +- repository: autowarefoundation/autoware_launch + files: + - source: autoware_launch/launch/autoware.launch.xml + - source: autoware_launch/launch/e2e_simulator.launch.xml + - source: autoware_launch/launch/logging_simulator.launch.xml + - source: autoware_launch/launch/planning_simulator.launch.xml + - source: autoware_launch/launch/pointcloud_container.launch.py + - source: autoware_launch/rviz/autoware.rviz + - source: autoware_launch/rviz/image/autoware.png + - source: autoware_launch/CMakeLists.txt + - source: autoware_launch/README.md + - source: autoware_launch/autoware_launch.drawio.svg + - source: autoware_launch/package.xml diff --git a/.github/workflows/sync-launch-files.yaml b/.github/workflows/sync-launch-files.yaml new file mode 100644 index 0000000000..4d573c5d9e --- /dev/null +++ b/.github/workflows/sync-launch-files.yaml @@ -0,0 +1,34 @@ +name: sync-files + +on: + schedule: + - cron: 0 0 * * * + workflow_dispatch: + +jobs: + check-secret: + uses: autowarefoundation/autoware-github-actions/.github/workflows/check-secret.yaml@v1 + secrets: + secret: ${{ secrets.APP_ID }} + + sync-files: + needs: check-secret + if: ${{ needs.check-secret.outputs.set == 'true' }} + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-files + uses: autowarefoundation/autoware-github-actions/sync-files@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + config: .github/sync-launch-files.yaml + pr-labels: | + bot + sync-files + auto-merge-method: squash From f76efa33adac27b7c4f62ca07ee8c89333c1c4ee Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 10 Nov 2022 17:35:02 +0900 Subject: [PATCH 672/851] ci: fix workflow name (#548) Signed-off-by: kminoda Signed-off-by: kminoda --- .github/workflows/sync-launch-files.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/sync-launch-files.yaml b/.github/workflows/sync-launch-files.yaml index 4d573c5d9e..e3772d752a 100644 --- a/.github/workflows/sync-launch-files.yaml +++ b/.github/workflows/sync-launch-files.yaml @@ -1,4 +1,4 @@ -name: sync-files +name: sync-launch-files on: schedule: From dad2a8c34af0792e1834f6606cbfd0e48ea7eac6 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 10 Nov 2022 17:47:30 +0900 Subject: [PATCH 673/851] fix: add some parameters for sync-launch-files workflow (#549) * fix: add some parameters for sync-launch-files workflow Signed-off-by: kminoda * Update .github/workflows/sync-launch-files.yaml Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Signed-off-by: kminoda Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .github/workflows/sync-launch-files.yaml | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/.github/workflows/sync-launch-files.yaml b/.github/workflows/sync-launch-files.yaml index e3772d752a..1c54e26f3e 100644 --- a/.github/workflows/sync-launch-files.yaml +++ b/.github/workflows/sync-launch-files.yaml @@ -28,7 +28,10 @@ jobs: with: token: ${{ steps.generate-token.outputs.token }} config: .github/sync-launch-files.yaml + pr-branch: sync-launch-files + pr-title: "chore: sync launch files" + pr-commit-message: "chore: sync launch files" pr-labels: | bot - sync-files + sync-launch-files auto-merge-method: squash From e3e094dfbbdd453444e0317bc3cc8d7dd57fc8f3 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 10 Nov 2022 21:56:42 +0900 Subject: [PATCH 674/851] feat: apply change of operation mode transition manager (#545) Signed-off-by: Takagi, Isamu Signed-off-by: Takagi, Isamu --- .../operation_mode_transition_manager.param.yaml | 1 + control_launch/launch/control.launch.py | 4 +--- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml b/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml index d42e2392be..be18812b59 100644 --- a/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml +++ b/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + transition_timeout: 3.0 frequency_hz: 10.0 engage_acceptable_limits: allow_autonomous_in_stopped: true # no check if the velocity is zero, always allowed. diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index d58be09a25..3003617d51 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -133,7 +133,7 @@ def launch_setup(context, *args, **kwargs): remappings=[ ("input/emergency_state", "/system/emergency/emergency_state"), ("input/steering", "/vehicle/status/steering_status"), - ("input/operation_mode", "/control/operation_mode"), + ("input/operation_mode", "/system/operation_mode/state"), ("input/auto/control_cmd", "/control/trajectory_follower/control_cmd"), ("input/auto/turn_indicators_cmd", "/planning/turn_indicators_cmd"), ("input/auto/hazard_lights_cmd", "/planning/hazard_lights_cmd"), @@ -187,10 +187,8 @@ def launch_setup(context, *args, **kwargs): ("control_cmd", "/control/command/control_cmd"), ("control_mode_report", "/vehicle/status/control_mode"), ("gate_operation_mode", "/control/vehicle_cmd_gate/operation_mode"), - ("operation_mode_request", "/system/operation_mode_request"), # output ("is_autonomous_available", "/control/is_autonomous_available"), - ("operation_mode", "/control/operation_mode"), ("control_mode_request", "/control/control_mode_request"), ], parameters=[ From ca53ef8cb4165ff63704b6a926b74816f91694ab Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Fri, 11 Nov 2022 14:40:11 +0900 Subject: [PATCH 675/851] feat!: use tier4_vehicle_launch instead of vehicle_launch (#538) * feat: use tier4_vehicle_launch * feat: delete * fix package.xml --- autoware_launch/launch/autoware.launch.xml | 5 +- .../launch/logging_simulator.launch.xml | 3 +- .../launch/planning_simulator.launch.xml | 5 +- autoware_launch/package.xml | 2 +- vehicle_launch/CMakeLists.txt | 18 ----- vehicle_launch/README.md | 65 ------------------- vehicle_launch/launch/vehicle.launch.xml | 28 -------- .../launch/vehicle_description.launch.xml | 15 ----- vehicle_launch/package.xml | 25 ------- vehicle_launch/urdf/vehicle.xacro | 16 ----- vehicle_launch/vehicle_launch.drawio.svg | 4 -- 11 files changed, 11 insertions(+), 175 deletions(-) delete mode 100644 vehicle_launch/CMakeLists.txt delete mode 100644 vehicle_launch/README.md delete mode 100644 vehicle_launch/launch/vehicle.launch.xml delete mode 100644 vehicle_launch/launch/vehicle_description.launch.xml delete mode 100644 vehicle_launch/package.xml delete mode 100644 vehicle_launch/urdf/vehicle.xacro delete mode 100644 vehicle_launch/vehicle_launch.drawio.svg diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 5b14dd9849..daee5d1f31 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -4,6 +4,8 @@ + + @@ -29,10 +31,11 @@ - + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 1e06453a48..65c153c3d3 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -44,11 +44,12 @@ - + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index d6fb815672..f5291f3e5e 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -4,6 +4,8 @@ + + @@ -30,10 +32,11 @@ - + + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 037f453faa..66defd0733 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -23,7 +23,7 @@ system_launch tier4_map_launch tier4_sensing_launch - vehicle_launch + tier4_vehicle_launch web_controller ament_lint_auto diff --git a/vehicle_launch/CMakeLists.txt b/vehicle_launch/CMakeLists.txt deleted file mode 100644 index f7f9c23733..0000000000 --- a/vehicle_launch/CMakeLists.txt +++ /dev/null @@ -1,18 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(vehicle_launch) - -add_compile_options(-std=c++14) - -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 - urdf -) diff --git a/vehicle_launch/README.md b/vehicle_launch/README.md deleted file mode 100644 index 837c12d023..0000000000 --- a/vehicle_launch/README.md +++ /dev/null @@ -1,65 +0,0 @@ -# vehicle_launch - -## Structure - -![vehicle_launch](./vehicle_launch.drawio.svg) - -## Package Dependencies - -Please see `` in `package.xml`. - -## Usage - -You can include as follows in `*.launch.xml` to use `vehicle.launch.xml`. - -```xml - - - - - - - -``` - -## Notes - -This package finds some external packages and settings with variables and package names. - -ex.) - - - -```xml - -``` - - - -```xml - -``` - -## vehicle.xacro - -### Arguments - -| Name | Type | Description | Default | -| ------------- | ------ | ------------------ | ------- | -| sensor_model | String | sensor model name | "" | -| vehicle_model | String | vehicle model name | "" | - -### Usage - -You can write as follows in `*.launch.xml`. - -```xml - - - - - - - - -``` diff --git a/vehicle_launch/launch/vehicle.launch.xml b/vehicle_launch/launch/vehicle.launch.xml deleted file mode 100644 index 24a3a19d81..0000000000 --- a/vehicle_launch/launch/vehicle.launch.xml +++ /dev/null @@ -1,28 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/vehicle_launch/launch/vehicle_description.launch.xml b/vehicle_launch/launch/vehicle_description.launch.xml deleted file mode 100644 index 5a2bd35382..0000000000 --- a/vehicle_launch/launch/vehicle_description.launch.xml +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/vehicle_launch/package.xml b/vehicle_launch/package.xml deleted file mode 100644 index c598670ac7..0000000000 --- a/vehicle_launch/package.xml +++ /dev/null @@ -1,25 +0,0 @@ - - - vehicle_launch - 0.1.0 - The vehicle_launch package - - Yukihiro Saito - Apache License 2.0 - - ament_cmake_auto - - camera_description - imu_description - livox_description - robot_state_publisher - velodyne_description - xacro - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - 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 @@ - - - - - - - - - - - - - - - diff --git a/vehicle_launch/vehicle_launch.drawio.svg b/vehicle_launch/vehicle_launch.drawio.svg deleted file mode 100644 index 13acf18829..0000000000 --- a/vehicle_launch/vehicle_launch.drawio.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - -
    vehicle.launch.xml

    package: vehicle_launch
    vehicle.launch.xml...
    vehicle_description.launch.xml

    package: vehicle_launch
    vehicle_description.launch.xml...
    vehicle_interface.launch.xml

    package: $(var vehicle_model)_description
    vehicle_interface.launch.xml...
    False
    False
    $(var simulation)
    $(var simulation)
    vehicle.xacro

    package: vehicle_launch
      
    vehicle.xacro...
    vehicle.xacro

    package: $(var vehicle_model)_description
    vehicle.xacro...
    sensors.xacro

    package: $(var sensor_model)_description
    sensors.xacro...
    launch name

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

    package: package name
    node name...
    robot state_publisher

    package: robot_state_publisher
    robot state_publisher...
    other name

    package: package name
    other name...
    Viewer does not support full SVG 1.1
    \ No newline at end of file From 8ff8f150113ff5da13327f67bfe6605d261d6023 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 11 Nov 2022 14:56:07 +0900 Subject: [PATCH 676/851] fix(localization_launch): add regularization default param (#552) * fix(localization_launch): add regularization default param Signed-off-by: kminoda * same format with universe Signed-off-by: kminoda Signed-off-by: kminoda --- localization_launch/config/ndt_scan_matcher.param.yaml | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/localization_launch/config/ndt_scan_matcher.param.yaml b/localization_launch/config/ndt_scan_matcher.param.yaml index 2ace1e86c5..e38f75a3f8 100644 --- a/localization_launch/config/ndt_scan_matcher.param.yaml +++ b/localization_launch/config/ndt_scan_matcher.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + # Vehicle reference frame base_frame: "base_link" @@ -57,3 +58,9 @@ 0.0, 0.0, 0.0, 0.0, 0.000625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000625, ] + + # Regularization switch + regularization_enabled: false + + # Regularization scale factor + regularization_scale_factor: 0.01 From dfe3337ef94c60779c6916a6a0b1c14910214398 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Sun, 13 Nov 2022 15:14:22 +0900 Subject: [PATCH 677/851] =?UTF-8?q?feat(motion=5Fvelocity=5Fsmoother):=20t?= =?UTF-8?q?unable=20deceleration=20limit=20for=20curve=20=E2=80=A6=20(#556?= =?UTF-8?q?)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat(motion_velocity_smoother): tunable deceleration limit for curve deceleration[ Signed-off-by: Takamasa Horibe Signed-off-by: Takamasa Horibe --- .../motion_velocity_smoother/motion_velocity_smoother.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index d95c9992c8..b2592316f6 100644 --- a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -12,6 +12,7 @@ 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 + min_decel_for_lateral_acc_lim_filter: -2.5 # deceleration limit applied in the lateral acceleration filter to avoid sudden braking [m/ss] # engage & replan parameters replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s] From e1ed86006d6410268fcc35bd1e39c6a2c61d1ab0 Mon Sep 17 00:00:00 2001 From: Makoto Kurihara Date: Mon, 14 Nov 2022 13:51:42 +0900 Subject: [PATCH 678/851] feat(system_launch): add a selector for multiple MRM behaviors (#557) Signed-off-by: Makoto Kurihara Signed-off-by: Makoto Kurihara --- control_launch/launch/control.launch.py | 1 + .../emergency_handler/emergency_handler.param.yaml | 12 ++++++++++++ system_launch/launch/system.launch.xml | 12 +++++++++++- 3 files changed, 24 insertions(+), 1 deletion(-) create mode 100644 system_launch/config/emergency_handler/emergency_handler.param.yaml diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 3003617d51..7c22e7e7a3 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -147,6 +147,7 @@ def launch_setup(context, *args, **kwargs): ("input/emergency/control_cmd", "/system/emergency/control_cmd"), ("input/emergency/hazard_lights_cmd", "/system/emergency/hazard_lights_cmd"), ("input/emergency/gear_cmd", "/system/emergency/gear_cmd"), + ("input/mrm_state", "/system/fail_safe/mrm_state"), ("output/vehicle_cmd_emergency", "/control/command/emergency_cmd"), ("output/control_cmd", "/control/command/control_cmd"), ("output/gear_cmd", "/control/command/gear_cmd"), diff --git a/system_launch/config/emergency_handler/emergency_handler.param.yaml b/system_launch/config/emergency_handler/emergency_handler.param.yaml new file mode 100644 index 0000000000..76ea50719a --- /dev/null +++ b/system_launch/config/emergency_handler/emergency_handler.param.yaml @@ -0,0 +1,12 @@ +/**: + ros__parameters: + update_rate: 10 + timeout_hazard_status: 0.5 + timeout_takeover_request: 10.0 + use_takeover_request: false + use_parking_after_stopped: false + use_comfortable_stop: false + + # setting whether to turn hazard lamp on for each situation + turning_hazard_on: + emergency: true diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index 88aaca8527..6ae14d5716 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -40,9 +40,19 @@
    + - + + + + + + + + + + From 03fa6d36918efc996a9f39f0d551941239faac22 Mon Sep 17 00:00:00 2001 From: Azumi Suzuki <38061530+s-azumi@users.noreply.github.com> Date: Tue, 15 Nov 2022 18:18:31 +0900 Subject: [PATCH 679/851] feat: set use_external_emergency_stop to false by default when launching psim (#540) * feat: set use_external_emergency_stop to false by default when launching psim Signed-off-by: Azumi Suzuki * feat: add comments Signed-off-by: Azumi Suzuki Signed-off-by: Azumi Suzuki --- autoware_launch/launch/planning_simulator.launch.xml | 2 ++ control_launch/launch/control.launch.xml | 2 ++ 2 files changed, 4 insertions(+) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index d6fb815672..2d0ca670d9 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -65,6 +65,8 @@ + +
    diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index db899b4573..ad2fb24a14 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -6,6 +6,7 @@ + @@ -14,6 +15,7 @@ +
    From 14f691029741784b74774b5396a4ff71d17f69ce Mon Sep 17 00:00:00 2001 From: Azumi Suzuki <38061530+s-azumi@users.noreply.github.com> Date: Tue, 15 Nov 2022 18:35:29 +0900 Subject: [PATCH 680/851] docs(README): fix dead links in README (#560) Signed-off-by: Azumi Suzuki Signed-off-by: Azumi Suzuki --- README.md | 1 - vehicle_launch/README.md | 4 ++-- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index b22428a818..3246a137bb 100644 --- a/README.md +++ b/README.md @@ -22,6 +22,5 @@ ros2 launch autoware_launch planning_simulator.launch.xml map_path:=/path/to/map - [localization_launch](./localization_launch) - [perception_launch](./perception_launch) - [planning_launch](./planning_launch) -- [sensing_launch](./sensing_launch) - [system_launch](./system_launch) - [vehicle_launch](./vehicle_launch) diff --git a/vehicle_launch/README.md b/vehicle_launch/README.md index 837c12d023..135e887a60 100644 --- a/vehicle_launch/README.md +++ b/vehicle_launch/README.md @@ -28,13 +28,13 @@ This package finds some external packages and settings with variables and packag ex.) - + ```xml ``` - + ```xml From 055dd9170d435e1bca563e9077c5d6a429939640 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 15 Nov 2022 18:39:20 +0900 Subject: [PATCH 681/851] feat: delete integration_launch (backport #537) (#563) feat: delete integration_launch (#537) (cherry picked from commit c04cc17401eced009290588e294c5dbc71f7c247) Co-authored-by: Hiroki OTA --- integration_launch/CMakeLists.txt | 16 -- integration_launch/README.md | 14 -- .../integration_launch.drawio.svg | 228 ------------------ .../launch/ci_planning_simulator.launch.xml | 31 --- integration_launch/launch/release.launch.xml | 19 -- integration_launch/package.xml | 30 --- 6 files changed, 338 deletions(-) delete mode 100644 integration_launch/CMakeLists.txt delete mode 100644 integration_launch/README.md delete mode 100644 integration_launch/integration_launch.drawio.svg delete mode 100644 integration_launch/launch/ci_planning_simulator.launch.xml delete mode 100644 integration_launch/launch/release.launch.xml delete mode 100644 integration_launch/package.xml diff --git a/integration_launch/CMakeLists.txt b/integration_launch/CMakeLists.txt deleted file mode 100644 index c3ddc04a7d..0000000000 --- a/integration_launch/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ - -cmake_minimum_required(VERSION 3.5) -project(integration_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/integration_launch/README.md b/integration_launch/README.md deleted file mode 100644 index 4a58b1b467..0000000000 --- a/integration_launch/README.md +++ /dev/null @@ -1,14 +0,0 @@ -# integration_launch - -## Structure - -![integration_launch](./integration_launch.drawio.svg) - -## Package Dependencies - -- autoware_launch -- scenario_runner - -## Notes - -This package is only used for continuous integration. diff --git a/integration_launch/integration_launch.drawio.svg b/integration_launch/integration_launch.drawio.svg deleted file mode 100644 index f40a0b345c..0000000000 --- a/integration_launch/integration_launch.drawio.svg +++ /dev/null @@ -1,228 +0,0 @@ - - - - - - - -
    -
    -
    - ci_planning_simulator.launch.xml -
    -
    -
    - - package: integration_launch - -
    -
    -
    -
    -
    - - ci_planning_simulator.launch.xml... - -
    -
    - - - - -
    -
    -
    - launch name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - launch name... - -
    -
    - - - - -
    -
    -
    - ex: -
    -
    -
    -
    - - ex: - -
    -
    - - - - -
    -
    -
    - node name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - node name... - -
    -
    - - - - -
    -
    -
    - planning_simulator.launch.xml -
    -
    -
    - - package: autoware_launch - -
    -
    -
    -
    -
    - - planning_simulator.launch.xml... - -
    -
    - - - - -
    -
    -
    - other name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - other name... - -
    -
    - - - - - - -
    -
    -
    - scenario_runner.launch.xml -
    -
    -
    - - package: scenario_runner - -
    -
    -
    -
    -
    - - scenario_runner.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - release.launch.xml -
    -
    -
    - - package: integration_launch - -
    -
    -
    -
    -
    - - release.launch.xml... - -
    -
    - - - - -
    -
    -
    - autoware.launch.xml -
    -
    -
    - - package: autoware_launch - -
    -
    -
    -
    -
    - - autoware.launch.xml... - -
    -
    - - -
    - - - - - Viewer does not support full SVG 1.1 - - - -
    \ No newline at end of file diff --git a/integration_launch/launch/ci_planning_simulator.launch.xml b/integration_launch/launch/ci_planning_simulator.launch.xml deleted file mode 100644 index 04ea5f3b73..0000000000 --- a/integration_launch/launch/ci_planning_simulator.launch.xml +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/integration_launch/launch/release.launch.xml b/integration_launch/launch/release.launch.xml deleted file mode 100644 index 3a27a1fa20..0000000000 --- a/integration_launch/launch/release.launch.xml +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/integration_launch/package.xml b/integration_launch/package.xml deleted file mode 100644 index 54d42a8492..0000000000 --- a/integration_launch/package.xml +++ /dev/null @@ -1,30 +0,0 @@ - - - integration_launch - 0.1.0 - The integration_launch package - - Hiroyuki Obinata - Apache 2 - ament_cmake_auto - - control_launch - localization_launch - perception_launch - planning_launch - python3-bson - python3-tornado - rviz2 - system_launch - tier4_map_launch - tier4_sensing_launch - vehicle_launch - web_controller - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - From d8c20f6980f2dfacac1a3efc5833469b4c5eb087 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 15 Nov 2022 18:42:13 +0900 Subject: [PATCH 682/851] feat!: use tier4_vehicle_launch instead of vehicle_launch (backport #538) (#562) feat!: use tier4_vehicle_launch instead of vehicle_launch (#538) * feat: use tier4_vehicle_launch * feat: delete * fix package.xml (cherry picked from commit ca53ef8cb4165ff63704b6a926b74816f91694ab) Co-authored-by: Hiroki OTA --- autoware_launch/launch/autoware.launch.xml | 5 +- .../launch/logging_simulator.launch.xml | 3 +- .../launch/planning_simulator.launch.xml | 5 +- autoware_launch/package.xml | 2 +- vehicle_launch/CMakeLists.txt | 18 ----- vehicle_launch/README.md | 65 ------------------- vehicle_launch/launch/vehicle.launch.xml | 28 -------- .../launch/vehicle_description.launch.xml | 15 ----- vehicle_launch/package.xml | 25 ------- vehicle_launch/urdf/vehicle.xacro | 16 ----- vehicle_launch/vehicle_launch.drawio.svg | 4 -- 11 files changed, 11 insertions(+), 175 deletions(-) delete mode 100644 vehicle_launch/CMakeLists.txt delete mode 100644 vehicle_launch/README.md delete mode 100644 vehicle_launch/launch/vehicle.launch.xml delete mode 100644 vehicle_launch/launch/vehicle_description.launch.xml delete mode 100644 vehicle_launch/package.xml delete mode 100644 vehicle_launch/urdf/vehicle.xacro delete mode 100644 vehicle_launch/vehicle_launch.drawio.svg diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 5b14dd9849..daee5d1f31 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -4,6 +4,8 @@ + + @@ -29,10 +31,11 @@ - + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 1e06453a48..65c153c3d3 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -44,11 +44,12 @@ - + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 2d0ca670d9..64d44edd76 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -4,6 +4,8 @@ + + @@ -30,10 +32,11 @@ - + + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 037f453faa..66defd0733 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -23,7 +23,7 @@ system_launch tier4_map_launch tier4_sensing_launch - vehicle_launch + tier4_vehicle_launch web_controller ament_lint_auto diff --git a/vehicle_launch/CMakeLists.txt b/vehicle_launch/CMakeLists.txt deleted file mode 100644 index f7f9c23733..0000000000 --- a/vehicle_launch/CMakeLists.txt +++ /dev/null @@ -1,18 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(vehicle_launch) - -add_compile_options(-std=c++14) - -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 - urdf -) diff --git a/vehicle_launch/README.md b/vehicle_launch/README.md deleted file mode 100644 index 135e887a60..0000000000 --- a/vehicle_launch/README.md +++ /dev/null @@ -1,65 +0,0 @@ -# vehicle_launch - -## Structure - -![vehicle_launch](./vehicle_launch.drawio.svg) - -## Package Dependencies - -Please see `` in `package.xml`. - -## Usage - -You can include as follows in `*.launch.xml` to use `vehicle.launch.xml`. - -```xml - - - - - - - -``` - -## Notes - -This package finds some external packages and settings with variables and package names. - -ex.) - - - -```xml - -``` - - - -```xml - -``` - -## vehicle.xacro - -### Arguments - -| Name | Type | Description | Default | -| ------------- | ------ | ------------------ | ------- | -| sensor_model | String | sensor model name | "" | -| vehicle_model | String | vehicle model name | "" | - -### Usage - -You can write as follows in `*.launch.xml`. - -```xml - - - - - - - - -``` diff --git a/vehicle_launch/launch/vehicle.launch.xml b/vehicle_launch/launch/vehicle.launch.xml deleted file mode 100644 index 24a3a19d81..0000000000 --- a/vehicle_launch/launch/vehicle.launch.xml +++ /dev/null @@ -1,28 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/vehicle_launch/launch/vehicle_description.launch.xml b/vehicle_launch/launch/vehicle_description.launch.xml deleted file mode 100644 index 5a2bd35382..0000000000 --- a/vehicle_launch/launch/vehicle_description.launch.xml +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/vehicle_launch/package.xml b/vehicle_launch/package.xml deleted file mode 100644 index c598670ac7..0000000000 --- a/vehicle_launch/package.xml +++ /dev/null @@ -1,25 +0,0 @@ - - - vehicle_launch - 0.1.0 - The vehicle_launch package - - Yukihiro Saito - Apache License 2.0 - - ament_cmake_auto - - camera_description - imu_description - livox_description - robot_state_publisher - velodyne_description - xacro - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - 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 @@ - - - - - - - - - - - - - - - diff --git a/vehicle_launch/vehicle_launch.drawio.svg b/vehicle_launch/vehicle_launch.drawio.svg deleted file mode 100644 index 13acf18829..0000000000 --- a/vehicle_launch/vehicle_launch.drawio.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - -
    vehicle.launch.xml

    package: vehicle_launch
    vehicle.launch.xml...
    vehicle_description.launch.xml

    package: vehicle_launch
    vehicle_description.launch.xml...
    vehicle_interface.launch.xml

    package: $(var vehicle_model)_description
    vehicle_interface.launch.xml...
    False
    False
    $(var simulation)
    $(var simulation)
    vehicle.xacro

    package: vehicle_launch
      
    vehicle.xacro...
    vehicle.xacro

    package: $(var vehicle_model)_description
    vehicle.xacro...
    sensors.xacro

    package: $(var sensor_model)_description
    sensors.xacro...
    launch name

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

    package: package name
    node name...
    robot state_publisher

    package: robot_state_publisher
    robot state_publisher...
    other name

    package: package name
    other name...
    Viewer does not support full SVG 1.1
    \ No newline at end of file From 61fe153c56a9e93d00ebd0d416f146e7a8bdd4c9 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Tue, 15 Nov 2022 19:01:40 +0900 Subject: [PATCH 683/851] docs: delete link for vehicle_launch (#566) --- README.md | 1 - 1 file changed, 1 deletion(-) diff --git a/README.md b/README.md index 3246a137bb..c88abfc7f8 100644 --- a/README.md +++ b/README.md @@ -23,4 +23,3 @@ ros2 launch autoware_launch planning_simulator.launch.xml map_path:=/path/to/map - [perception_launch](./perception_launch) - [planning_launch](./planning_launch) - [system_launch](./system_launch) -- [vehicle_launch](./vehicle_launch) From a5076ee40ff489f8fc9e1afc7ac7c3f05e226c6f Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Tue, 15 Nov 2022 19:49:30 +0900 Subject: [PATCH 684/851] fix: modified to reflect the argument "initial_selector_mode" in control launch (porting #496) (#564) fix: modified to reflect the argument "initial_selector_mode" in control launch (#496) Co-authored-by: Azumi Suzuki <38061530+s-azumi@users.noreply.github.com> --- control_launch/launch/control.launch.py | 2 +- control_launch/launch/control.launch.xml | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 7c22e7e7a3..55f159ddf3 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -206,7 +206,7 @@ def launch_setup(context, *args, **kwargs): launch_arguments=[ ("use_intra_process", LaunchConfiguration("use_intra_process")), ("target_container", "/control/control_container"), - ("initial_selector_mode", "remote"), + ("initial_selector_mode", LaunchConfiguration("initial_selector_mode")), ], ) diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index ad2fb24a14..ee4cd99d6e 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -6,6 +6,7 @@ + @@ -15,6 +16,7 @@ + From d0be11264cfe4aae04621b333e5ae1ecd2231946 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 17 Nov 2022 15:54:19 +0900 Subject: [PATCH 685/851] feat(system_launch): add component state monitor (#561) Signed-off-by: Takagi, Isamu Signed-off-by: Takagi, Isamu --- system_launch/launch/system.launch.xml | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index 6ae14d5716..ba8a835cb7 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -29,6 +29,14 @@
    + + + + + + + + From 3ae5fe3bedfeb13516257a1ddf22a27383baa082 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 18 Nov 2022 12:22:50 +0900 Subject: [PATCH 686/851] feat(planning_launch): add new param for avoidance (#558) Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- .../behavior_path_planner/avoidance/avoidance.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index 1b820b2c2b..b90ddf20bd 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -12,8 +12,10 @@ threshold_distance_object_is_on_center: 1.0 # [m] threshold_speed_object_is_stopped: 1.0 # [m/s] + threshold_time_object_is_moving: 1.0 # [s] object_check_forward_distance: 150.0 # [m] object_check_backward_distance: 2.0 # [m] + object_envelope_buffer: 0.3 # [m] lateral_collision_margin: 1.0 # [m] lateral_collision_safety_buffer: 0.7 # [m] From 03df5148810ad362e9077203b5be8735242c0c3e Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Fri, 18 Nov 2022 14:16:45 +0900 Subject: [PATCH 687/851] Feature/ad api/remove old routing launch (#526) feat: remove launch for old routing api Signed-off-by: Takagi, Isamu Signed-off-by: Takagi, Isamu --- .../launch/include/internal_api_adaptor.launch.py | 1 - 1 file changed, 1 deletion(-) diff --git a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py index 422c35abee..f1962908c8 100644 --- a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py +++ b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py @@ -31,7 +31,6 @@ def generate_launch_description(): components = [ _create_api_node("iv_msgs", "IVMsgs"), _create_api_node("operator", "Operator"), - _create_api_node("route", "Route"), _create_api_node("velocity", "Velocity"), ] container = ComposableNodeContainer( From 4b0cebb3d6d768802a94aff58599672020e45d63 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Tue, 22 Nov 2022 16:44:30 +0900 Subject: [PATCH 688/851] fix: add obstacle stop param to launch (#570) Signed-off-by: tomoya.kimura Signed-off-by: tomoya.kimura --- autoware_launch/launch/logging_simulator.launch.xml | 2 ++ autoware_launch/launch/planning_simulator.launch.xml | 5 ++++- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 65c153c3d3..f966932c13 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -23,6 +23,7 @@ + @@ -100,6 +101,7 @@ + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 64d44edd76..7ff1b4afbe 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -11,6 +11,7 @@ + @@ -58,7 +59,9 @@ - + + + From 02d6a90fdbe9dfe2d4477e8ab4194e1c8be4261a Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Thu, 24 Nov 2022 10:49:32 +0900 Subject: [PATCH 689/851] chore: sync files (#551) Signed-off-by: GitHub Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 2 +- .github/workflows/cancel-previous-workflows.yaml | 2 +- .markdown-link-check.json | 3 +++ .markdownlint.yaml | 2 ++ .pre-commit-config-optional.yaml | 2 +- 5 files changed, 8 insertions(+), 3 deletions(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index a44ef48d1d..2b9e80f9f1 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -78,7 +78,7 @@ jobs: - name: Get modified files id: get-modified-files - uses: tj-actions/changed-files@v32 + uses: tj-actions/changed-files@v34 with: files: | **/*.cpp diff --git a/.github/workflows/cancel-previous-workflows.yaml b/.github/workflows/cancel-previous-workflows.yaml index b28a4ec0bb..f9c29b81b6 100644 --- a/.github/workflows/cancel-previous-workflows.yaml +++ b/.github/workflows/cancel-previous-workflows.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Cancel previous runs - uses: styfle/cancel-workflow-action@0.10.1 + uses: styfle/cancel-workflow-action@0.11.0 with: workflow_id: all all_but_latest: true diff --git a/.markdown-link-check.json b/.markdown-link-check.json index dec3db1ad1..c71a3e4253 100644 --- a/.markdown-link-check.json +++ b/.markdown-link-check.json @@ -4,6 +4,9 @@ { "pattern": "^http://localhost" }, + { + "pattern": "^http://127\\.0\\.0\\.1" + }, { "pattern": "^https://github.com/.*/discussions/new" } diff --git a/.markdownlint.yaml b/.markdownlint.yaml index df1f518dc0..babaaa1f15 100644 --- a/.markdownlint.yaml +++ b/.markdownlint.yaml @@ -3,6 +3,8 @@ default: true MD013: false MD024: siblings_only: true +MD029: + style: ordered MD033: false MD041: false MD046: false diff --git a/.pre-commit-config-optional.yaml b/.pre-commit-config-optional.yaml index a805f1201c..e0019e10d5 100644 --- a/.pre-commit-config-optional.yaml +++ b/.pre-commit-config-optional.yaml @@ -1,6 +1,6 @@ repos: - repo: https://github.com/tcort/markdown-link-check - rev: v3.10.0 + rev: v3.10.3 hooks: - id: markdown-link-check args: [--config=.markdown-link-check.json] From 60152380e74e0a8dabf4080c9849cb80632cdc0e Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 24 Nov 2022 14:14:10 +0900 Subject: [PATCH 690/851] feat(system_launch): apply removing ad_service_state_monitor (#568) Signed-off-by: Takagi, Isamu Signed-off-by: Takagi, Isamu --- .github/sync-param-files.yaml | 8 +- .../ad_service_state_monitor.param.yaml | 155 ---- ...ate_monitor.planning_simulation.param.yaml | 126 ---- .../component_state_monitor/topics.yaml | 182 +++++ system_launch/launch/system.launch.xml | 13 +- system_launch/package.xml | 2 +- system_launch/system_launch.drawio.svg | 712 ++++++++---------- 7 files changed, 499 insertions(+), 699 deletions(-) delete mode 100644 system_launch/config/ad_service_state_monitor.param.yaml delete mode 100644 system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml create mode 100644 system_launch/config/component_state_monitor/topics.yaml diff --git a/.github/sync-param-files.yaml b/.github/sync-param-files.yaml index 876c31cf0b..8e6565ec96 100644 --- a/.github/sync-param-files.yaml +++ b/.github/sync-param-files.yaml @@ -1,11 +1,9 @@ - repository: tier4/autoware.universe files: # system - ## ad_service_state_monitor - - source: system/ad_service_state_monitor/config/ad_service_state_monitor.param.yaml - dest: system_launch/config/ad_service_state_monitor.param.yaml - - source: system/ad_service_state_monitor/config/ad_service_state_monitor.planning_simulation.param.yaml - dest: system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml + ## component_state_monitor + - source: system/component_state_monitor/config/topics.yaml + dest: system_launch/config/component_state_monitor/topics.yaml ## system_error_monitor - source: system/system_error_monitor/config/system_error_monitor.param.yaml diff --git a/system_launch/config/ad_service_state_monitor.param.yaml b/system_launch/config/ad_service_state_monitor.param.yaml deleted file mode 100644 index bfbb6beeaf..0000000000 --- a/system_launch/config/ad_service_state_monitor.param.yaml +++ /dev/null @@ -1,155 +0,0 @@ -# AD Service State Monitor Parameters -/**: - ros__parameters: - # modules_names: string array - module_names: [ - "map", - "sensing", - "perception", - "localization", - "planning", - "control", - "vehicle", - "system" - ] - - # Topic Config - ## names: string array - ## configs: top level - ### names used to declare parameter group - #### module: string - #### timeout[s]: double (0: none) - #### warn_rate[hz]: double (0: none) - topic_configs: - names: [ - "/map/vector_map", - "/map/pointcloud_map", - "/perception/obstacle_segmentation/pointcloud", - "/initialpose3d", - "/localization/pose_twist_fusion_filter/pose", - "/perception/object_recognition/objects", - "/planning/mission_planning/route", - "/planning/scenario_planning/trajectory", - "/control/trajectory_follower/control_cmd", - "/control/command/control_cmd", - "/vehicle/status/velocity_status", - "/vehicle/status/steering_status", - "/system/emergency/control_cmd" - ] - - configs: - /map/vector_map: - module: "map" - timeout: 0.0 - warn_rate: 0.0 - type: "autoware_auto_mapping_msgs/msg/HADMapBin" - transient_local: True - - /map/pointcloud_map: - module: "map" - timeout: 0.0 - warn_rate: 0.0 - type: "sensor_msgs/msg/PointCloud2" - transient_local: True - - /perception/obstacle_segmentation/pointcloud: - module: "sensing" - timeout: 1.0 - warn_rate: 5.0 - type: "sensor_msgs/msg/PointCloud2" - best_effort: True - - /initialpose3d: - module: "localization" - timeout: 0.0 - warn_rate: 0.0 - type: "geometry_msgs/msg/PoseWithCovarianceStamped" - - /localization/pose_twist_fusion_filter/pose: - module: "localization" - timeout: 1.0 - warn_rate: 5.0 - type: "geometry_msgs/msg/PoseStamped" - - # Can be both with feature array or without - # In prediction.launch.xml this is set to without - /perception/object_recognition/objects: - module: "perception" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_perception_msgs/msg/PredictedObjects" - # This topic could have two different types depending on the launch flags used. - # The implementation of subscriptions in ROS2 does not allow for multiple types - # to be defined for a topic. By default this is set to not use have features. - # type: ["tier4_perception_msgs/msg/DynamicObjectArray", "tier4_perception_msgs/msg/DynamicObjectWithFeatureArray"] - - /planning/mission_planning/route: - module: "planning" - timeout: 0.0 - warn_rate: 0.0 - type: "autoware_auto_planning_msgs/msg/HADMapRoute" - transient_local: True - - /planning/scenario_planning/trajectory: - module: "planning" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_planning_msgs/msg/Trajectory" - - /control/trajectory_follower/control_cmd: - module: "control" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_control_msgs/msg/AckermannControlCommand" - - /control/command/control_cmd: - module: "control" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_control_msgs/msg/AckermannControlCommand" - - /vehicle/status/velocity_status: - module: "vehicle" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_vehicle_msgs/msg/VelocityReport" - - /vehicle/status/steering_status: - module: "vehicle" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_vehicle_msgs/msg/SteeringReport" - - /system/emergency/control_cmd: - module: "system" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_control_msgs/msg/AckermannControlCommand" - - # Param Config - ## names: string array - ## configs: top level - ### names used to declare parameter group - #### module: string - # param_configs: - # names: ["/vehicle_info"] - # configs: - # /vehicle_info: - # module: "vehicle" - - # TF Config - ## names: string array - ## configs: top level - ### names used to declare parameter group - #### module: string - #### from: string - #### to: string - #### timeout[s]: double (0: none) - tf_configs: - names: ["map_to_base_link"] - configs: - map_to_base_link: - module: "localization" - from: "map" - to: "base_link" - timeout: 1.0 diff --git a/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml b/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml deleted file mode 100644 index 51fbe99dd9..0000000000 --- a/system_launch/config/ad_service_state_monitor.planning_simulation.param.yaml +++ /dev/null @@ -1,126 +0,0 @@ -# AD Service State Monitor: Planning Simulator Parameters -/**: - ros__parameters: - # modules_names: string array - module_names: [ - "map", - "sensing", - "perception", - "localization", - "planning", - "control", - "vehicle", - "system" - ] - -# Topic Config - ## names: string array - ## configs: top level - ### names used to declare parameter group - #### module: string - #### timeout[s]: double (0: none) - #### warn_rate[hz]: double (0: none) - topic_configs: - names: [ - "/map/vector_map", - "/perception/object_recognition/objects", - "/initialpose3d", - "/planning/mission_planning/route", - "/planning/scenario_planning/trajectory", - "/control/trajectory_follower/control_cmd", - "/control/command/control_cmd", - "/vehicle/status/velocity_status", - "/vehicle/status/steering_status", - "/system/emergency/control_cmd" - ] - - configs: - /map/vector_map: - module: "map" - timeout: 0.0 - warn_rate: 0.0 - type: "autoware_auto_mapping_msgs/msg/HADMapBin" - transient_local: True - - /perception/object_recognition/objects: - module: "perception" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_perception_msgs/msg/PredictedObjects" - - /initialpose3d: - module: "localization" - timeout: 0.0 - warn_rate: 0.0 - type: "geometry_msgs/msg/PoseWithCovarianceStamped" - - /planning/mission_planning/route: - module: "planning" - timeout: 0.0 - warn_rate: 0.0 - type: "autoware_auto_planning_msgs/msg/HADMapRoute" - transient_local: True - - /planning/scenario_planning/trajectory: - module: "planning" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_planning_msgs/msg/Trajectory" - - /control/trajectory_follower/control_cmd: - module: "control" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_control_msgs/msg/AckermannControlCommand" - - /control/command/control_cmd: - module: "control" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_control_msgs/msg/AckermannControlCommand" - - /vehicle/status/velocity_status: - module: "vehicle" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_vehicle_msgs/msg/VelocityReport" - - /vehicle/status/steering_status: - module: "vehicle" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_vehicle_msgs/msg/SteeringReport" - - /system/emergency/control_cmd: - module: "system" - timeout: 1.0 - warn_rate: 5.0 - type: "autoware_auto_control_msgs/msg/AckermannControlCommand" - - # Param Config - ## names: string array - ## configs: top level - ### names used to declare parameter group - #### module: string - # param_configs: - # names: ["/vehicle_info"] - # configs: - # /vehicle_info: - # module: "vehicle" - - # TF Config - ## names: string array - ## configs: top level - ### names used to declare parameter group - #### module: string - #### from: string - #### to: string - #### timeout[s]: double (0: none) - tf_configs: - names: ["map_to_base_link"] - configs: - map_to_base_link: - module: "localization" - from: "map" - to: "base_link" - timeout: 1.0 diff --git a/system_launch/config/component_state_monitor/topics.yaml b/system_launch/config/component_state_monitor/topics.yaml new file mode 100644 index 0000000000..b55dfa5aec --- /dev/null +++ b/system_launch/config/component_state_monitor/topics.yaml @@ -0,0 +1,182 @@ +- module: map + mode: [online, planning_simulation] + type: launch + args: + node_name_suffix: vector_map + topic: /map/vector_map + topic_type: autoware_auto_mapping_msgs/msg/HADMapBin + best_effort: false + transient_local: true + warn_rate: 0.0 + error_rate: 0.0 + timeout: 0.0 + +- module: map + mode: [online] + type: launch + args: + node_name_suffix: pointcloud_map + topic: /map/pointcloud_map + topic_type: sensor_msgs/msg/PointCloud2 + best_effort: false + transient_local: true + warn_rate: 0.0 + error_rate: 0.0 + timeout: 0.0 + +- module: localization + mode: [online, planning_simulation] + type: autonomous + args: + node_name_suffix: initialpose3d + topic: /initialpose3d + topic_type: geometry_msgs/msg/PoseWithCovarianceStamped + best_effort: false + transient_local: false + warn_rate: 0.0 + error_rate: 0.0 + timeout: 0.0 + +- module: localization + mode: [online] + type: autonomous + args: + node_name_suffix: pose_twist_fusion_filter_pose + topic: /localization/pose_twist_fusion_filter/pose + topic_type: geometry_msgs/msg/PoseStamped + best_effort: false + transient_local: false + warn_rate: 5.0 + error_rate: 1.0 + timeout: 1.0 + +- module: perception + mode: [online] + type: launch + args: + node_name_suffix: obstacle_segmentation_pointcloud + topic: /perception/obstacle_segmentation/pointcloud + topic_type: sensor_msgs/msg/PointCloud2 + best_effort: true + transient_local: false + warn_rate: 5.0 + error_rate: 1.0 + timeout: 1.0 + +- module: perception + mode: [online, planning_simulation] + type: autonomous + args: + node_name_suffix: object_recognition_objects + topic: /perception/object_recognition/objects + topic_type: autoware_auto_perception_msgs/msg/PredictedObjects + best_effort: false + transient_local: false + warn_rate: 5.0 + error_rate: 1.0 + timeout: 1.0 + +- module: planning + mode: [online, planning_simulation] + type: autonomous + args: + node_name_suffix: mission_planning_route + topic: /planning/mission_planning/route + topic_type: autoware_auto_planning_msgs/msg/HADMapRoute + best_effort: false + transient_local: true + warn_rate: 0.0 + error_rate: 0.0 + timeout: 0.0 + +- module: planning + mode: [online, planning_simulation] + type: autonomous + args: + node_name_suffix: scenario_planning_trajectory + topic: /planning/scenario_planning/trajectory + topic_type: autoware_auto_planning_msgs/msg/Trajectory + best_effort: false + transient_local: false + warn_rate: 5.0 + error_rate: 1.0 + timeout: 1.0 + +- module: control + mode: [online, planning_simulation] + type: autonomous + args: + node_name_suffix: trajectory_follower_control_cmd + topic: /control/trajectory_follower/control_cmd + topic_type: autoware_auto_control_msgs/msg/AckermannControlCommand + best_effort: false + transient_local: false + warn_rate: 5.0 + error_rate: 1.0 + timeout: 1.0 + +- module: control + mode: [online, planning_simulation] + type: autonomous + args: + node_name_suffix: control_command_control_cmd + topic: /control/command/control_cmd + topic_type: autoware_auto_control_msgs/msg/AckermannControlCommand + best_effort: false + transient_local: false + warn_rate: 5.0 + error_rate: 1.0 + timeout: 1.0 + +- module: vehicle + mode: [online, planning_simulation] + type: autonomous + args: + node_name_suffix: vehicle_status_velocity_status + topic: /vehicle/status/velocity_status + topic_type: autoware_auto_vehicle_msgs/msg/VelocityReport + best_effort: false + transient_local: false + warn_rate: 5.0 + error_rate: 1.0 + timeout: 1.0 + +- module: vehicle + mode: [online, planning_simulation] + type: autonomous + args: + node_name_suffix: vehicle_status_steering_status + topic: /vehicle/status/steering_status + topic_type: autoware_auto_vehicle_msgs/msg/SteeringReport + best_effort: false + transient_local: false + warn_rate: 5.0 + error_rate: 1.0 + timeout: 1.0 + +- module: system + mode: [online, planning_simulation] + type: launch + args: + node_name_suffix: system_emergency_control_cmd + topic: /system/emergency/control_cmd + topic_type: autoware_auto_control_msgs/msg/AckermannControlCommand + best_effort: false + transient_local: false + warn_rate: 5.0 + error_rate: 1.0 + timeout: 1.0 + +- module: localization + mode: [online, planning_simulation] + type: autonomous + args: + node_name_suffix: transform_map_to_base_link + topic: /tf + frame_id: map + child_frame_id: base_link + best_effort: false + transient_local: false + warn_rate: 5.0 + error_rate: 1.0 + timeout: 1.0 diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index ba8a835cb7..982a49ea96 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -22,12 +22,13 @@ - - - - - - + + + + + + + diff --git a/system_launch/package.xml b/system_launch/package.xml index 7f8169ed5e..9d3e90ad2d 100644 --- a/system_launch/package.xml +++ b/system_launch/package.xml @@ -10,7 +10,7 @@ ament_cmake_auto - ad_service_state_monitor + component_state_monitor emergency_handler system_error_monitor system_monitor diff --git a/system_launch/system_launch.drawio.svg b/system_launch/system_launch.drawio.svg index bc039dbba8..334012a85b 100644 --- a/system_launch/system_launch.drawio.svg +++ b/system_launch/system_launch.drawio.svg @@ -1,408 +1,308 @@ - - - - - - - -
    -
    -
    - system.launch.xml -
    -
    -
    - - package: system_launch - -
    -
    -
    -
    -
    - - system.launch.xml... - -
    -
    - - - - -
    -
    -
    - system_monitor.launch.py -
    -
    -
    - package: system_monitor -
    -
    -
    -
    -
    - - system_monitor.launch.py... - -
    -
    - - - - - - - - - -
    -
    -
    - online -
    -
    -
    -
    - - online - -
    -
    - - - - - -
    -
    -
    - planning_simulation -
    -
    -
    -
    - - planning_simulation - -
    -
    - - - - -
    -
    -
    - $(var run_mode) -
    -
    -
    -
    - - $(var run_mode) - -
    -
    - - - - -
    -
    -
    - launch name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - launch name... - -
    -
    - - - - -
    -
    -
    - ex: -
    -
    -
    -
    - - ex: - -
    -
    - - - - -
    -
    -
    - node name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - node name... - -
    -
    - - - - -
    -
    -
    - other name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - other name... - -
    -
    - - - - -
    -
    -
    - ad_service_state_monitor.launch.xml -
    -
    -
    - package: ad_service_state_monitor -
    -
    -
    -
    -
    - args: config_file = - - ad_service_state_monitor.param.yaml - -
    -
    -
    -
    -
    - - ad_service_state_monitor.launch.xml... - -
    -
    - - - - -
    -
    -
    - ad_service_state_monitor.launch.xml -
    -
    -
    - package: ad_service_state_monitor -
    -
    -
    -
    -
    - args: config_file = - - ad_service_state_monitor.planning_simulation.param.yaml - -
    -
    -
    -
    -
    - - ad_service_state_monitor.launch.xml... - -
    -
    - - - - - - - -
    -
    -
    - online -
    -
    -
    -
    - - online - -
    -
    - - - - - -
    -
    -
    - planning_simulation -
    -
    -
    -
    - - planning_simulation - -
    -
    - - - - -
    -
    -
    - $(var run_mode) -
    -
    -
    -
    - - $(var run_mode) - -
    -
    - - - - -
    -
    -
    - system_error_monitor.launch.xml -
    -
    -
    - package: system_error_monitor -
    -
    -
    -
    -
    - args: config_file = - - system_error_monitor.param.yaml - -
    -
    -
    -
    -
    - - system_error_monitor.launch.xml... - -
    -
    - - - - -
    -
    -
    - system_error_monitor.launch.xml -
    -
    -
    - package: system_error_monitor -
    -
    -
    -
    -
    - args: config_file = - - system_error_monitor.planning_simulation.param.yaml - -
    -
    -
    -
    -
    - - system_error_monitor.launch.xml... - -
    -
    - - - - -
    -
    -
    - emergency_handler.launch.xml -
    -
    -
    - package: emergency_handler -
    -
    -
    -
    -
    - - emergency_handler.launch.xml... - -
    -
    - - + + + + + + + + + + + + + + + +
    +
    +
    + system.launch.xml +
    +
    +
    + package: system_launch +
    +
    +
    +
    +
    + system.launch.xml... +
    - - - - - Viewer does not support full SVG 1.1 - - - + + + + +
    +
    +
    + system_monitor.launch.py +
    +
    +
    package: system_monitor
    +
    +
    +
    +
    + system_monitor.launch.py... +
    +
    + + + + +
    +
    +
    + launch name +
    +
    +
    + package: package name +
    +
    +
    +
    +
    + launch name... +
    +
    + + + + +
    +
    +
    + ex: +
    +
    +
    +
    + ex: +
    +
    + + + + +
    +
    +
    + node name +
    +
    +
    + package: package name +
    +
    +
    +
    +
    + node name... +
    +
    + + + + +
    +
    +
    + other name +
    +
    +
    + package: package name +
    +
    +
    +
    +
    + other name... +
    +
    + + + + +
    +
    +
    + component_state_monitor.launch.py +
    +
    +
    + package: + component_state_monitor +
    +
    +
    +
    +
    + component_state_monitor.launch.py... +
    +
    + + + + + +
    +
    +
    + online +
    +
    +
    +
    + online +
    +
    + + + + + +
    +
    +
    + planning_simulation +
    +
    +
    +
    + planning_simulation +
    +
    + + + + +
    +
    +
    + $(var run_mode) +
    +
    +
    +
    + $(var run_mode) +
    +
    + + + + +
    +
    +
    + autoware_error_monitor.launch.xml +
    +
    +
    package: autoware_error_monitor
    +
    +
    +
    +
    + args: config_file = + autoware_error_monitor.param.yaml +
    +
    +
    +
    +
    + autoware_error_monitor.launch.xml... +
    +
    + + + + +
    +
    +
    + autoware_error_monitor.launch.xml +
    +
    +
    package: autoware_error_monitor
    +
    +
    +
    +
    + args: config_file = + autoware_error_monitor.planning_simulation.param.yaml +
    +
    +
    +
    +
    + autoware_error_monitor.launch.xml... +
    +
    + + + + +
    +
    +
    + emergency_handler.launch.xml +
    +
    +
    package: emergency_handler
    +
    +
    +
    +
    + emergency_handler.launch.xml... +
    +
    +
    + + + + Viewer does not support full SVG 1.1 + +
    From e497c422b40f4d754d00408b967e07a250591ae8 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Thu, 24 Nov 2022 15:15:20 +0900 Subject: [PATCH 691/851] feat(system_launch): add group tag around include (#573) Signed-off-by: Tomohito Ando Signed-off-by: Tomohito Ando --- system_launch/launch/system.launch.xml | 43 ++++++++++++++------------ 1 file changed, 24 insertions(+), 19 deletions(-) diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index 982a49ea96..28ad1a28e0 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -39,29 +39,34 @@
    - - - - - - - - + + + + + + + + + + - - - - + + + + + + - - - - - - - + + + + + + + + From 9dcccf64f5cf6a7b76058a5e5b28b5b237ddc946 Mon Sep 17 00:00:00 2001 From: Makoto Kurihara Date: Fri, 25 Nov 2022 15:10:38 +0900 Subject: [PATCH 692/851] feat(planning_launch): add steering rate limit params (#575) feat(planning_launch): add steering rate limit configs Signed-off-by: Makoto Kurihara Signed-off-by: Makoto Kurihara --- .../config/trajectory_follower/mpc_follower.param.yaml | 2 +- .../motion_velocity_smoother.param.yaml | 8 +++++++- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/control_launch/config/trajectory_follower/mpc_follower.param.yaml b/control_launch/config/trajectory_follower/mpc_follower.param.yaml index 4085f7025b..5298e2b330 100644 --- a/control_launch/config/trajectory_follower/mpc_follower.param.yaml +++ b/control_launch/config/trajectory_follower/mpc_follower.param.yaml @@ -44,7 +44,7 @@ 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 approximation) [s] - steer_rate_lim_dps: 600.0 # steering angle rate limit [deg/s] + steer_rate_lim_dps: 40.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] diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index b2592316f6..a2b9255ef3 100644 --- a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -48,5 +48,11 @@ post_sparse_resample_dt: 0.1 # resample time interval for sparse sampling [s] post_sparse_min_interval_distance: 1.0 # minimum points-interval length for sparse sampling [m] + # steering angle rate limit parameters + max_steering_angle_rate: 40.0 # maximum steering angle rate [degree/s] + resample_ds: 0.1 # distance between trajectory points [m] + curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m] + curvature_calculation_distance: 1.0 # distance of points while curvature is calculating [m] + # system - over_stop_velocity_warn_thr: 1.389 # used to check if the optimization exceeds the input velocity on the stop point + over_stop_velocity_warn_thr: 1.389 # used to check if the optimization exceeds the input velocity on the stop point From c7c04ea5a6afc9f81cb60ffeeb73a03fe5b431f8 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 25 Nov 2022 17:38:49 +0900 Subject: [PATCH 693/851] fix(planning_launch): revise lane change parameters (#567) * fix(planning_launch): revise lane change parameters Signed-off-by: Muhammad Zulfaqar Azmi * disable collision check at prepare phase Signed-off-by: Muhammad Zulfaqar Azmi * enable collision check at prepare and no use all predicted Signed-off-by: Muhammad Zulfaqar Azmi * reduced front expected deceleration Signed-off-by: Muhammad Zulfaqar Azmi * additional config Signed-off-by: Muhammad Zulfaqar Azmi * fixed lateral and longitudinal value Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_planner/behavior_path_planner.param.yaml | 4 ++-- .../behavior_path_planner/lane_change/lane_change.param.yaml | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index b9c50b15e5..252cb5451d 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -27,9 +27,9 @@ visualize_drivable_area_for_shared_linestrings_lanelet: true - lateral_distance_max_threshold: 5.0 + lateral_distance_max_threshold: 2.0 longitudinal_distance_min_threshold: 3.0 - expected_front_deceleration: -1.0 + expected_front_deceleration: -0.5 expected_rear_deceleration: -1.0 rear_vehicle_reaction_time: 2.0 rear_vehicle_safety_time_margin: 2.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml index a1ad81b61e..fc8b314b09 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -3,7 +3,7 @@ lane_change: lane_change_prepare_duration: 4.0 # [s] lane_changing_duration: 8.0 # [s] - minimum_lane_change_prepare_distance: 4.0 # [m] + minimum_lane_change_prepare_distance: 2.0 # [m] lane_change_finish_judge_buffer: 3.0 # [m] minimum_lane_change_velocity: 5.6 # [m/s] prediction_time_resolution: 0.5 # [s] @@ -15,5 +15,5 @@ enable_abort_lane_change: true enable_collision_check_at_prepare_phase: true use_predicted_path_outside_lanelet: true - use_all_predicted_path: true + use_all_predicted_path: false publish_debug_marker: false From 8c5f2d424bc28223093d822fc9fac489a24d3a56 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 25 Nov 2022 19:42:47 +0900 Subject: [PATCH 694/851] feat(planning_launch): abort deceleration for abort param (#576) * feat(planning_launch): abort deceleration for abort param Signed-off-by: Muhammad Zulfaqar Azmi * rename parameter to make is expressive Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_planner/behavior_path_planner.param.yaml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index 252cb5451d..b32e4e1b67 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -31,5 +31,9 @@ longitudinal_distance_min_threshold: 3.0 expected_front_deceleration: -0.5 expected_rear_deceleration: -1.0 + + expected_front_deceleration_for_abort: -2.0 + expected_rear_deceleration_for_abort: -2.5 + rear_vehicle_reaction_time: 2.0 rear_vehicle_safety_time_margin: 2.0 From d7b5273c2aff7feeaab5a3ce261a97bb1184e314 Mon Sep 17 00:00:00 2001 From: Makoto Kurihara Date: Fri, 25 Nov 2022 23:03:44 +0900 Subject: [PATCH 695/851] feat(system_launch): add mrm operator's configs to system_launch (#574) Signed-off-by: Makoto Kurihara Signed-off-by: Makoto Kurihara --- .../mrm_comfortable_stop_operator.param.yaml | 6 ++++++ .../mrm_emergency_stop_operator.param.yaml | 5 +++++ system_launch/launch/system.launch.xml | 8 ++++++-- 3 files changed, 17 insertions(+), 2 deletions(-) create mode 100644 system_launch/config/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator.param.yaml create mode 100644 system_launch/config/mrm_emergency_stop_operator/mrm_emergency_stop_operator.param.yaml diff --git a/system_launch/config/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator.param.yaml b/system_launch/config/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator.param.yaml new file mode 100644 index 0000000000..81bc9b9c0b --- /dev/null +++ b/system_launch/config/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator.param.yaml @@ -0,0 +1,6 @@ +/**: + ros__parameters: + update_rate: 10 + min_acceleration: -1.0 + max_jerk: 0.3 + min_jerk: -0.3 diff --git a/system_launch/config/mrm_emergency_stop_operator/mrm_emergency_stop_operator.param.yaml b/system_launch/config/mrm_emergency_stop_operator/mrm_emergency_stop_operator.param.yaml new file mode 100644 index 0000000000..1ee2699a23 --- /dev/null +++ b/system_launch/config/mrm_emergency_stop_operator/mrm_emergency_stop_operator.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + update_rate: 30 + target_acceleration: -2.5 + target_jerk: -1.5 diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index 28ad1a28e0..0696bbfaa2 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -60,11 +60,15 @@ + - + + + + - + From 98db139243cf02f19781c4b0ede36dedb35de28e Mon Sep 17 00:00:00 2001 From: Makoto Kurihara Date: Fri, 25 Nov 2022 23:04:53 +0900 Subject: [PATCH 696/851] feat(system_launch): split system_error_monitor config for simulation (#577) Signed-off-by: Makoto Kurihara Signed-off-by: Makoto Kurihara --- .../system_error_monitor.param.yaml | 0 ...ror_monitor.planning_simulation.param.yaml | 49 +++++++++++++++++++ system_launch/launch/system.launch.xml | 7 ++- 3 files changed, 55 insertions(+), 1 deletion(-) rename system_launch/config/{ => system_error_monitor}/system_error_monitor.param.yaml (100%) create mode 100644 system_launch/config/system_error_monitor/system_error_monitor.planning_simulation.param.yaml diff --git a/system_launch/config/system_error_monitor.param.yaml b/system_launch/config/system_error_monitor/system_error_monitor.param.yaml similarity index 100% rename from system_launch/config/system_error_monitor.param.yaml rename to system_launch/config/system_error_monitor/system_error_monitor.param.yaml diff --git a/system_launch/config/system_error_monitor/system_error_monitor.planning_simulation.param.yaml b/system_launch/config/system_error_monitor/system_error_monitor.planning_simulation.param.yaml new file mode 100644 index 0000000000..27fd3c1e4d --- /dev/null +++ b/system_launch/config/system_error_monitor/system_error_monitor.planning_simulation.param.yaml @@ -0,0 +1,49 @@ +# name: diag name +# sf_at: diag level where it becomes Safe Fault +# lf_at: diag level where it becomes Latent Fault +# spf_at: diag level where it becomes Single Point Fault +# auto_recovery: Determines whether the system will automatically recover when it recovers from an error. +# +# Note: +# empty-value for sf_at, lf_at and spf_at is "none" +# default values are: +# sf_at: "none" +# lf_at: "warn" +# spf_at: "error" +# auto_recovery: "true" +--- +/**: + ros__parameters: + required_modules: + autonomous_driving: + /autoware/control/autonomous_driving/node_alive_monitoring: default + /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default + /autoware/control/control_command_gate/node_alive_monitoring: default + + /autoware/localization/node_alive_monitoring: default + /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } + /autoware/localization/performance_monitoring/localization_accuracy: default + + /autoware/map/node_alive_monitoring: default + + /autoware/perception/node_alive_monitoring: default + + /autoware/planning/node_alive_monitoring: default + /autoware/planning/performance_monitoring/trajectory_validation: default + + # /autoware/sensing/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "none", spf_at: "none" } + + /autoware/vehicle/node_alive_monitoring: default + + external_control: + /autoware/control/control_command_gate/node_alive_monitoring: default + /autoware/control/external_control/external_command_selector/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + + /autoware/vehicle/node_alive_monitoring: default diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index 0696bbfaa2..ef0b5b63fc 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -40,7 +40,12 @@ - + + From 787c39aeb42aa057af229cdb29584dd0ddfb47de Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 28 Nov 2022 14:35:10 +0900 Subject: [PATCH 697/851] fix(system_launch): fix dupilcated-launched component_state_monitor (#581) Signed-off-by: tomoya.kimura Signed-off-by: tomoya.kimura --- system_launch/launch/system.launch.xml | 8 -------- 1 file changed, 8 deletions(-) diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index ef0b5b63fc..c2ea378a7f 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -30,14 +30,6 @@ - - - - - - - - From a6cd8624df7e654b7100505f5cff43beec2bb1ee Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 28 Nov 2022 17:59:49 +0900 Subject: [PATCH 698/851] feat(planning_launch): add obstacle_avoidance_planner param (#579) Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../obstacle_avoidance_planner.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 50f5caa048..9290aa3c0a 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -39,6 +39,8 @@ num_fix_points_for_extending: 50 # number of fixing points when extending max_dist_for_extending_end_point: 0.0001 # minimum delta dist thres for extending last point [m] + non_fixed_trajectory_length: 5.0 # length of the trajectory merging optimized mpt trajectory to original(not optimized) trajectory + object: # avoiding object max_avoiding_objects_velocity_ms: 0.5 # maximum velocity for avoiding objects [m/s] max_avoiding_ego_velocity_ms: 6.0 # maximum ego velocity when avoiding objects [m/s] From db57d520305921c5f1f3d7eda04b9c36cbe9f81f Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Tue, 29 Nov 2022 16:48:49 +0900 Subject: [PATCH 699/851] feat: change operation mode transition timeout (#584) Signed-off-by: Takagi, Isamu Signed-off-by: Takagi, Isamu --- .../operation_mode_transition_manager.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml b/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml index be18812b59..45014428d0 100644 --- a/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml +++ b/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml @@ -1,6 +1,6 @@ /**: ros__parameters: - transition_timeout: 3.0 + transition_timeout: 10.0 frequency_hz: 10.0 engage_acceptable_limits: allow_autonomous_in_stopped: true # no check if the velocity is zero, always allowed. From 5e394870327ebb38581c80a4258a4275e0ab947e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 29 Nov 2022 16:59:15 +0900 Subject: [PATCH 700/851] feat(planning_launch): add option of clipping fixed trajectory (#580) * feat(planning_launch): add option of clipping fixed trajectory Signed-off-by: Takayuki Murooka * Update obstacle_avoidance_planner.param.yaml Signed-off-by: Takayuki Murooka --- .../obstacle_avoidance_planner.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 9290aa3c0a..a18e531806 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -39,6 +39,7 @@ num_fix_points_for_extending: 50 # number of fixing points when extending max_dist_for_extending_end_point: 0.0001 # minimum delta dist thres for extending last point [m] + enable_clipping_fixed_traj: false non_fixed_trajectory_length: 5.0 # length of the trajectory merging optimized mpt trajectory to original(not optimized) trajectory object: # avoiding object From 894d26a59ec07db7ef25c32dedab2532cfa4d684 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 30 Nov 2022 11:34:37 +0900 Subject: [PATCH 701/851] feat!: replace HADMap with Lanelet (#571) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- system_launch/config/component_state_monitor/topics.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system_launch/config/component_state_monitor/topics.yaml b/system_launch/config/component_state_monitor/topics.yaml index b55dfa5aec..5a5f2e880b 100644 --- a/system_launch/config/component_state_monitor/topics.yaml +++ b/system_launch/config/component_state_monitor/topics.yaml @@ -82,7 +82,7 @@ args: node_name_suffix: mission_planning_route topic: /planning/mission_planning/route - topic_type: autoware_auto_planning_msgs/msg/HADMapRoute + topic_type: autoware_planning_msgs/msg/LaneletRoute best_effort: false transient_local: true warn_rate: 0.0 From 66429de93c1d8764379fb8dbbac8ce8c31436aa3 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 1 Dec 2022 23:23:26 +0900 Subject: [PATCH 702/851] ci(pre-commit): autoupdate (#407) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit updates: - [github.com/pre-commit/pre-commit-hooks: v4.3.0 → v4.4.0](https://github.com/pre-commit/pre-commit-hooks/compare/v4.3.0...v4.4.0) - [github.com/igorshubovych/markdownlint-cli: v0.31.1 → v0.32.2](https://github.com/igorshubovych/markdownlint-cli/compare/v0.31.1...v0.32.2) - [github.com/pre-commit/mirrors-prettier: v2.7.1 → v3.0.0-alpha.4](https://github.com/pre-commit/mirrors-prettier/compare/v2.7.1...v3.0.0-alpha.4) - [github.com/adrienverge/yamllint: v1.26.3 → v1.28.0](https://github.com/adrienverge/yamllint/compare/v1.26.3...v1.28.0) - [github.com/psf/black: 22.6.0 → 22.10.0](https://github.com/psf/black/compare/22.6.0...22.10.0) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .pre-commit-config.yaml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 9f08293e43..bb390fbd4a 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -4,7 +4,7 @@ ci: repos: - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.3.0 + rev: v4.4.0 hooks: - id: check-json - id: check-merge-conflict @@ -18,18 +18,18 @@ repos: args: [--markdown-linebreak-ext=md] - repo: https://github.com/igorshubovych/markdownlint-cli - rev: v0.31.1 + rev: v0.32.2 hooks: - id: markdownlint args: [-c, .markdownlint.yaml, --fix] - repo: https://github.com/pre-commit/mirrors-prettier - rev: v2.7.1 + rev: v3.0.0-alpha.4 hooks: - id: prettier - repo: https://github.com/adrienverge/yamllint - rev: v1.26.3 + rev: v1.28.0 hooks: - id: yamllint @@ -57,7 +57,7 @@ repos: - id: isort - repo: https://github.com/psf/black - rev: 22.6.0 + rev: 22.10.0 hooks: - id: black args: [--line-length=100] From fa3ebc1bdc608f3d56c7bf0b6a02f4d1d16b4e94 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Thu, 1 Dec 2022 23:35:23 +0900 Subject: [PATCH 703/851] chore: sync files (#587) Signed-off-by: GitHub Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 4 ---- .github/workflows/build-and-test.yaml | 4 ---- 2 files changed, 8 deletions(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 2b9e80f9f1..24b34530f0 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -11,12 +11,8 @@ jobs: fail-fast: false matrix: rosdistro: - - galactic - humble include: - - rosdistro: galactic - container: ros:galactic - build-depends-repos: build_depends.repos - rosdistro: humble container: ros:humble build-depends-repos: build_depends.repos diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 161e3ba227..6459a98044 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -15,12 +15,8 @@ jobs: fail-fast: false matrix: rosdistro: - - galactic - humble include: - - rosdistro: galactic - container: ros:galactic - build-depends-repos: build_depends.repos - rosdistro: humble container: ros:humble build-depends-repos: build_depends.repos From c7460372d8b5be5cb446cf7729d06dd03ecf62a7 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 2 Dec 2022 09:32:27 +0900 Subject: [PATCH 704/851] feat(planning_launch): add new param to avoidance.param.yaml (#569) * feat(planning_launch): add new param to avoidance.param.yaml Signed-off-by: satoshi-ota * fix(planning_launch): reorder params for readability Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- .../avoidance/avoidance.param.yaml | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index b90ddf20bd..4fe82e3a05 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -10,11 +10,19 @@ enable_avoidance_over_same_direction: true enable_avoidance_over_opposite_direction: true - threshold_distance_object_is_on_center: 1.0 # [m] + # For target object filtering threshold_speed_object_is_stopped: 1.0 # [m/s] threshold_time_object_is_moving: 1.0 # [s] + object_check_forward_distance: 150.0 # [m] object_check_backward_distance: 2.0 # [m] + + threshold_distance_object_is_on_center: 1.0 # [m] + + object_check_shiftable_ratio: 0.6 # [-] + object_check_min_road_shoulder_width: 0.5 # [m] + + # For lateral margin object_envelope_buffer: 0.3 # [m] lateral_collision_margin: 1.0 # [m] lateral_collision_safety_buffer: 0.7 # [m] From b32d2ed49618b9b5cb2cb0d036e870306f424543 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 6 Dec 2022 13:57:19 +0900 Subject: [PATCH 705/851] feat(transition_manager): add param to ignore autonomous transition condition (#591) Signed-off-by: Takamasa Horibe Signed-off-by: Takamasa Horibe --- .../operation_mode_transition_manager.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml b/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml index 45014428d0..a0ddef6e36 100644 --- a/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml +++ b/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml @@ -2,6 +2,7 @@ ros__parameters: transition_timeout: 10.0 frequency_hz: 10.0 + check_engage_condition: false # set false if you do not want to care about the engage condition. engage_acceptable_limits: allow_autonomous_in_stopped: true # no check if the velocity is zero, always allowed. dist_threshold: 1.5 From b672bc74ede0b174d0bbdf630652fe9e7a8440ce Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 7 Dec 2022 20:25:45 +0900 Subject: [PATCH 706/851] feat(autoware_launch): remove web_controller (#593) Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- autoware_launch/launch/autoware.launch.xml | 3 --- autoware_launch/launch/logging_simulator.launch.xml | 3 --- autoware_launch/launch/planning_simulator.launch.xml | 3 --- autoware_launch/package.xml | 1 - 4 files changed, 10 deletions(-) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index daee5d1f31..105aeea3f4 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -115,8 +115,5 @@ if="$(var rviz)" /> - - - diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index f966932c13..d40700521b 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -130,8 +130,5 @@ if="$(var rviz)" /> - - - diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 7ff1b4afbe..e6bbf391a0 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -93,9 +93,6 @@ if="$(var rviz)" /> - - - diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 66defd0733..2fa28bd87a 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -24,7 +24,6 @@ tier4_map_launch tier4_sensing_launch tier4_vehicle_launch - web_controller ament_lint_auto autoware_lint_common From f11809dd04a6be7de15f1726bf45ab91688819a7 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 8 Dec 2022 00:28:56 +0900 Subject: [PATCH 707/851] fix(autoware_api_launch): add rosbridge_server dependency (#594) Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- autoware_api_launch/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_api_launch/package.xml b/autoware_api_launch/package.xml index 71a37f44f0..ef6f3e838a 100644 --- a/autoware_api_launch/package.xml +++ b/autoware_api_launch/package.xml @@ -14,6 +14,7 @@ awapi_awiv_adapter default_ad_api path_distance_calculator + rosbridge_server topic_tools ament_lint_auto From e87e14ccdfc5721da5fc616f9e2f2555bc828f8a Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 9 Dec 2022 17:55:18 +0900 Subject: [PATCH 708/851] feat(planning_launch): add behavior_velocity_limiter to motion_planning launch file (#596) Signed-off-by: Maxime CLEMENT Signed-off-by: Maxime CLEMENT --- .../obstacle_velocity_limiter.param.yaml | 33 +++++++++++++++ .../motion_planning/motion_planning.launch.py | 41 +++++++++++++++++-- 2 files changed, 71 insertions(+), 3 deletions(-) create mode 100644 planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml new file mode 100644 index 0000000000..c6a0c275db --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml @@ -0,0 +1,33 @@ +/**: + ros__parameters: + min_ttc: 1.0 # [s] minimum time without collision when doing projection at each trajectory point + distance_buffer: 0.0 # [m] extra distance to add to a projection (in addition to the vehicle overhang) + min_adjusted_velocity: 2.5 # [m/s] minimum velocity that the module can set + max_deceleration: 2.0 # [m/s²] maximum deceleration caused by the adjusted velocity + + trajectory_preprocessing: + start_distance: 0.0 # [m] distance ahead of ego from which to start modifying the trajectory + max_length: 100.0 # [m] maximum distance (from the start point) where the velocity is adjusted + max_duration: 10.0 # [s] maximum duration (from the start point) where the velocity is adjusted + downsample_factor: 10 # factor by which to downsample the input trajectory for calculation + calculate_steering_angles: false # if true, the steering angle at each trajectory point is calculated from the change in heading + + simulation: + model: particle # model to use for forward projection at each trajectory point. Either "particle" or "bicycle" + distance_method: exact # distance calculation method. Either "exact" or "approximation". + # parameters used only with the bicycle model + steering_offset: 0.01 # [rad] steering angle offset used to model uncertainty in the forward projection + nb_points: 5 # number of points representing the curved projections + + obstacles: + dynamic_source: static_only # source of dynamic obstacles. Must be 'pointcloud', 'occupancy_grid', or 'static_only'. + ignore_obstacles_on_path: false # if true, obstacles on the ego paths are ignored + ignore_extra_distance: 1.0 # [m] extra lateral distance where obstacles along the path are ignored + occupancy_grid_threshold: 60 # occupancy grid values higher than this are considered to be obstacles + dynamic_obstacles_buffer: 1.5 # [m] extra distance around dynamic obstacles used to mask the occupancy grid and avoid false obstacle detection + dynamic_obstacles_min_vel: 0.5 # [m/s] velocity above which a dynamic obstacle is ignored by the module + static_map_tags: # linestring tags in the lanelet maps that will be used as static obstacles + - guard_rail + filter_envelope : false # whether to calculate the apparent safety envelope and use it to filter obstacles + rtree_min_points: 500 # from this number of obstacle points, a rtree is used for collision detection + rtree_min_segments: 1600 # from this number of obstacle segments, a rtree is used for collision detection diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index e1f27d2b44..56a2468124 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -94,6 +94,40 @@ def add_launch_arg(name: str, default_value=None, description=None): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + # obstacle velocity limiter + obstacle_velocity_limiter_param_path = os.path.join( + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "motion_planning", + "obstacle_velocity_limiter", + "obstacle_velocity_limiter.param.yaml", + ) + with open(obstacle_velocity_limiter_param_path, "r") as f: + obstacle_velocity_limiter_param = yaml.safe_load(f)["/**"]["ros__parameters"] + obstacle_velocity_limiter_component = ComposableNode( + package="obstacle_velocity_limiter", + plugin="obstacle_velocity_limiter::ObstacleVelocityLimiterNode", + name="obstacle_velocity_limiter", + namespace="", + remappings=[ + ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), + ("~/input/odometry", "/localization/kinematic_state"), + ("~/input/dynamic_obstacles", "/perception/object_recognition/objects"), + ("~/input/occupancy_grid", "/perception/occupancy_grid_map/map"), + ("~/input/obstacle_pointcloud", "/perception/obstacle_segmentation/pointcloud"), + ("~/input/map", "/map/vector_map"), + ("~/output/debug_markers", "debug_markers"), + ("~/output/trajectory", "obstacle_velocity_limiter/trajectory"), + ], + parameters=[ + obstacle_velocity_limiter_param, + {"obstacles.dynamic_source": "static_only"}, + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + # surround obstacle checker surround_obstacle_checker_param_path = os.path.join( get_package_share_directory("planning_launch"), @@ -151,7 +185,7 @@ def add_launch_arg(name: str, default_value=None, description=None): name="obstacle_cruise_planner", namespace="", remappings=[ - ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), + ("~/input/trajectory", "obstacle_velocity_limiter/trajectory"), ("~/input/odometry", "/localization/kinematic_state"), ("~/input/acceleration", "/localization/acceleration"), ("~/input/objects", "/perception/object_recognition/objects"), @@ -212,7 +246,7 @@ def add_launch_arg(name: str, default_value=None, description=None): ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), + ("~/input/trajectory", "obstacle_velocity_limiter/trajectory"), ], parameters=[ common_param, @@ -230,7 +264,7 @@ def add_launch_arg(name: str, default_value=None, description=None): name="obstacle_cruise_planner_relay", namespace="", parameters=[ - {"input_topic": "obstacle_avoidance_planner/trajectory"}, + {"input_topic": "obstacle_velocity_limiter/trajectory"}, {"output_topic": "/planning/scenario_planning/lane_driving/trajectory"}, {"type": "autoware_auto_planning_msgs/msg/Trajectory"}, ], @@ -244,6 +278,7 @@ def add_launch_arg(name: str, default_value=None, description=None): executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ obstacle_avoidance_planner_component, + obstacle_velocity_limiter_component, ], ) From 0b14693b121d0d859dc24e089e7289af8735551f Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Fri, 9 Dec 2022 18:09:46 +0900 Subject: [PATCH 709/851] feat(planning_launch): add behavior_velocity_limiter to motion_planning launch file (#596) (#597) Signed-off-by: Maxime CLEMENT Signed-off-by: Maxime CLEMENT Signed-off-by: Maxime CLEMENT Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> --- .../obstacle_velocity_limiter.param.yaml | 33 +++++++++++++++ .../motion_planning/motion_planning.launch.py | 41 +++++++++++++++++-- 2 files changed, 71 insertions(+), 3 deletions(-) create mode 100644 planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml new file mode 100644 index 0000000000..c6a0c275db --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml @@ -0,0 +1,33 @@ +/**: + ros__parameters: + min_ttc: 1.0 # [s] minimum time without collision when doing projection at each trajectory point + distance_buffer: 0.0 # [m] extra distance to add to a projection (in addition to the vehicle overhang) + min_adjusted_velocity: 2.5 # [m/s] minimum velocity that the module can set + max_deceleration: 2.0 # [m/s²] maximum deceleration caused by the adjusted velocity + + trajectory_preprocessing: + start_distance: 0.0 # [m] distance ahead of ego from which to start modifying the trajectory + max_length: 100.0 # [m] maximum distance (from the start point) where the velocity is adjusted + max_duration: 10.0 # [s] maximum duration (from the start point) where the velocity is adjusted + downsample_factor: 10 # factor by which to downsample the input trajectory for calculation + calculate_steering_angles: false # if true, the steering angle at each trajectory point is calculated from the change in heading + + simulation: + model: particle # model to use for forward projection at each trajectory point. Either "particle" or "bicycle" + distance_method: exact # distance calculation method. Either "exact" or "approximation". + # parameters used only with the bicycle model + steering_offset: 0.01 # [rad] steering angle offset used to model uncertainty in the forward projection + nb_points: 5 # number of points representing the curved projections + + obstacles: + dynamic_source: static_only # source of dynamic obstacles. Must be 'pointcloud', 'occupancy_grid', or 'static_only'. + ignore_obstacles_on_path: false # if true, obstacles on the ego paths are ignored + ignore_extra_distance: 1.0 # [m] extra lateral distance where obstacles along the path are ignored + occupancy_grid_threshold: 60 # occupancy grid values higher than this are considered to be obstacles + dynamic_obstacles_buffer: 1.5 # [m] extra distance around dynamic obstacles used to mask the occupancy grid and avoid false obstacle detection + dynamic_obstacles_min_vel: 0.5 # [m/s] velocity above which a dynamic obstacle is ignored by the module + static_map_tags: # linestring tags in the lanelet maps that will be used as static obstacles + - guard_rail + filter_envelope : false # whether to calculate the apparent safety envelope and use it to filter obstacles + rtree_min_points: 500 # from this number of obstacle points, a rtree is used for collision detection + rtree_min_segments: 1600 # from this number of obstacle segments, a rtree is used for collision detection diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index e1f27d2b44..56a2468124 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -94,6 +94,40 @@ def add_launch_arg(name: str, default_value=None, description=None): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + # obstacle velocity limiter + obstacle_velocity_limiter_param_path = os.path.join( + get_package_share_directory("planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "motion_planning", + "obstacle_velocity_limiter", + "obstacle_velocity_limiter.param.yaml", + ) + with open(obstacle_velocity_limiter_param_path, "r") as f: + obstacle_velocity_limiter_param = yaml.safe_load(f)["/**"]["ros__parameters"] + obstacle_velocity_limiter_component = ComposableNode( + package="obstacle_velocity_limiter", + plugin="obstacle_velocity_limiter::ObstacleVelocityLimiterNode", + name="obstacle_velocity_limiter", + namespace="", + remappings=[ + ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), + ("~/input/odometry", "/localization/kinematic_state"), + ("~/input/dynamic_obstacles", "/perception/object_recognition/objects"), + ("~/input/occupancy_grid", "/perception/occupancy_grid_map/map"), + ("~/input/obstacle_pointcloud", "/perception/obstacle_segmentation/pointcloud"), + ("~/input/map", "/map/vector_map"), + ("~/output/debug_markers", "debug_markers"), + ("~/output/trajectory", "obstacle_velocity_limiter/trajectory"), + ], + parameters=[ + obstacle_velocity_limiter_param, + {"obstacles.dynamic_source": "static_only"}, + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + # surround obstacle checker surround_obstacle_checker_param_path = os.path.join( get_package_share_directory("planning_launch"), @@ -151,7 +185,7 @@ def add_launch_arg(name: str, default_value=None, description=None): name="obstacle_cruise_planner", namespace="", remappings=[ - ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), + ("~/input/trajectory", "obstacle_velocity_limiter/trajectory"), ("~/input/odometry", "/localization/kinematic_state"), ("~/input/acceleration", "/localization/acceleration"), ("~/input/objects", "/perception/object_recognition/objects"), @@ -212,7 +246,7 @@ def add_launch_arg(name: str, default_value=None, description=None): ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), + ("~/input/trajectory", "obstacle_velocity_limiter/trajectory"), ], parameters=[ common_param, @@ -230,7 +264,7 @@ def add_launch_arg(name: str, default_value=None, description=None): name="obstacle_cruise_planner_relay", namespace="", parameters=[ - {"input_topic": "obstacle_avoidance_planner/trajectory"}, + {"input_topic": "obstacle_velocity_limiter/trajectory"}, {"output_topic": "/planning/scenario_planning/lane_driving/trajectory"}, {"type": "autoware_auto_planning_msgs/msg/Trajectory"}, ], @@ -244,6 +278,7 @@ def add_launch_arg(name: str, default_value=None, description=None): executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ obstacle_avoidance_planner_component, + obstacle_velocity_limiter_component, ], ) From c896f3f1aa80f822756ff0838a9f967522433441 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Fri, 9 Dec 2022 19:38:54 +0900 Subject: [PATCH 710/851] fix(planning_launch): add dependency (#598) Signed-off-by: tomoya.kimura Signed-off-by: tomoya.kimura --- planning_launch/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/package.xml b/planning_launch/package.xml index ccb151e6cb..e8e473ca5d 100644 --- a/planning_launch/package.xml +++ b/planning_launch/package.xml @@ -18,6 +18,7 @@ motion_velocity_smoother obstacle_avoidance_planner obstacle_stop_planner + obstacle_velocity_limiter scenario_selector surround_obstacle_checker From acb358e0408977617a066ef84a036f3db8cc69e3 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Mon, 12 Dec 2022 16:04:14 +0900 Subject: [PATCH 711/851] feat: use xml for system monitor launch (#602) * feat: use xml for system monitor launch Signed-off-by: Daisuke Nishimatsu * ci(pre-commit): autofix * fix voltage monitor param path Signed-off-by: Daisuke Nishimatsu Signed-off-by: Daisuke Nishimatsu Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/system_monitor/voltage_monitor.param.yaml | 5 +++++ system_launch/launch/system.launch.xml | 3 ++- 2 files changed, 7 insertions(+), 1 deletion(-) create mode 100644 system_launch/config/system_monitor/voltage_monitor.param.yaml diff --git a/system_launch/config/system_monitor/voltage_monitor.param.yaml b/system_launch/config/system_monitor/voltage_monitor.param.yaml new file mode 100644 index 0000000000..e55410be39 --- /dev/null +++ b/system_launch/config/system_monitor/voltage_monitor.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + cmos_battery_warn: 2.90 + cmos_battery_error: 2.70 + cmos_battery_label: "" diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index c2ea378a7f..7360aadb0a 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -11,7 +11,7 @@ - + @@ -19,6 +19,7 @@ + From e80a89dd4f9348bf35c3f8bb59da2bbed7ad8a5a Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Mon, 12 Dec 2022 18:02:40 +0900 Subject: [PATCH 712/851] feat(behavior_path_planner): add a flag to clip left and right bound (#595) feat(behavior_path_planner): add bound clipping flag for objects Signed-off-by: yutaka Signed-off-by: yutaka --- .../behavior_path_planner/avoidance/avoidance.param.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index 4fe82e3a05..e698819fc9 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -48,6 +48,9 @@ min_avoidance_speed_for_acc_prevention: 3.0 # [m/s] max_avoidance_acceleration: 0.5 # [m/ss] + # bound clipping for objects + enable_bound_clipping: false + # for debug publish_debug_marker: false print_debug_info: false From e680e3ea235305da859e35f291f7d4ee0c9e3b00 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Mon, 12 Dec 2022 23:03:31 +0900 Subject: [PATCH 713/851] feat(rviz): add drivable area visualization (#603) * feat(rviz): add drivable area visualization Signed-off-by: yutaka * update Signed-off-by: yutaka * change name Signed-off-by: yutaka Signed-off-by: yutaka --- 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 c2282509ca..36bf7252d7 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1010,6 +1010,20 @@ Visualization Manager: Constant Color: false Scale: 0.30000001192092896 Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: Bound + Namespaces: + left_bound: true + right_bound: true + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/bound + Value: true - Class: rviz_common/Group Displays: - Class: rviz_default_plugins/MarkerArray From 62f871743911546d851668222abe0282d489bf97 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 13 Dec 2022 15:08:14 +0900 Subject: [PATCH 714/851] feat: add sync from awf-latest -> awf-latest-xx1 (#605) Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .github/workflows/sync-awf-latest-xx1.yaml | 31 ++++++++++++++++++++++ 1 file changed, 31 insertions(+) create mode 100644 .github/workflows/sync-awf-latest-xx1.yaml diff --git a/.github/workflows/sync-awf-latest-xx1.yaml b/.github/workflows/sync-awf-latest-xx1.yaml new file mode 100644 index 0000000000..f6d9da8591 --- /dev/null +++ b/.github/workflows/sync-awf-latest-xx1.yaml @@ -0,0 +1,31 @@ +name: sync-awf-latest-xx1 + +on: + schedule: + - cron: 0 0 * * * + workflow_dispatch: + +jobs: + sync-awf-latest-xx1: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + base-branch: awf-latest-xx1 + sync-pr-branch: sync-awf-latest-xx1 + sync-target-repository: https://github.com/tier4/autoware_launch.git + sync-target-branch: awf-latest + pr-title: "chore: sync awf-latest-xx1" + pr-labels: | + bot + sync-awf-latest-xx1 + auto-merge-method: merge From 8e597da88e25435c78072ce35d98be7e32b4a9ca Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 15 Dec 2022 10:53:14 +0900 Subject: [PATCH 715/851] feat: add sync from awf-latest -> awf-latest-reference-design (#613) Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .github/workflows/sync-awf-latest-s1.yaml | 31 +++++++++++++++++++++++ .github/workflows/sync-awf-latest-x1.yaml | 31 +++++++++++++++++++++++ .github/workflows/sync-awf-latest-x2.yaml | 31 +++++++++++++++++++++++ 3 files changed, 93 insertions(+) create mode 100644 .github/workflows/sync-awf-latest-s1.yaml create mode 100644 .github/workflows/sync-awf-latest-x1.yaml create mode 100644 .github/workflows/sync-awf-latest-x2.yaml diff --git a/.github/workflows/sync-awf-latest-s1.yaml b/.github/workflows/sync-awf-latest-s1.yaml new file mode 100644 index 0000000000..f34ce0ffa6 --- /dev/null +++ b/.github/workflows/sync-awf-latest-s1.yaml @@ -0,0 +1,31 @@ +name: sync-awf-latest-s1 + +on: + schedule: + - cron: 0 0 * * * + workflow_dispatch: + +jobs: + sync-awf-latest-s1: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + base-branch: awf-latest-s1 + sync-pr-branch: sync-awf-latest-s1 + sync-target-repository: https://github.com/tier4/autoware_launch.git + sync-target-branch: awf-latest + pr-title: "chore: sync awf-latest-s1" + pr-labels: | + bot + sync-awf-latest-s1 + auto-merge-method: merge diff --git a/.github/workflows/sync-awf-latest-x1.yaml b/.github/workflows/sync-awf-latest-x1.yaml new file mode 100644 index 0000000000..c51a13e917 --- /dev/null +++ b/.github/workflows/sync-awf-latest-x1.yaml @@ -0,0 +1,31 @@ +name: sync-awf-latest-x1 + +on: + schedule: + - cron: 0 0 * * * + workflow_dispatch: + +jobs: + sync-awf-latest-x1: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + base-branch: awf-latest-x1 + sync-pr-branch: sync-awf-latest-x1 + sync-target-repository: https://github.com/tier4/autoware_launch.git + sync-target-branch: awf-latest + pr-title: "chore: sync awf-latest-x1" + pr-labels: | + bot + sync-awf-latest-x1 + auto-merge-method: merge diff --git a/.github/workflows/sync-awf-latest-x2.yaml b/.github/workflows/sync-awf-latest-x2.yaml new file mode 100644 index 0000000000..910c5e8598 --- /dev/null +++ b/.github/workflows/sync-awf-latest-x2.yaml @@ -0,0 +1,31 @@ +name: sync-awf-latest-x2 + +on: + schedule: + - cron: 0 0 * * * + workflow_dispatch: + +jobs: + sync-awf-latest-x2: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + base-branch: awf-latest-x2 + sync-pr-branch: sync-awf-latest-x2 + sync-target-repository: https://github.com/tier4/autoware_launch.git + sync-target-branch: awf-latest + pr-title: "chore: sync awf-latest-x2" + pr-labels: | + bot + sync-awf-latest-x2 + auto-merge-method: merge From 85d0c88645a18ab66a4e8c5d0e0cd8c8013c4d4f Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 15 Dec 2022 17:29:52 +0900 Subject: [PATCH 716/851] feat(trajectory_follower): extend mpc trajectory for terminal yaw (#611) * feat(trajectory_follower): extend mpc trajectory for terminal yaw Signed-off-by: kosuke55 * rename to extend_trajectory_for_end_yaw_control Signed-off-by: kosuke55 * Update control_launch/config/trajectory_follower/mpc_follower.param.yaml Signed-off-by: kosuke55 --- .../config/trajectory_follower/mpc_follower.param.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/control_launch/config/trajectory_follower/mpc_follower.param.yaml b/control_launch/config/trajectory_follower/mpc_follower.param.yaml index 5298e2b330..4b4f348a5a 100644 --- a/control_launch/config/trajectory_follower/mpc_follower.param.yaml +++ b/control_launch/config/trajectory_follower/mpc_follower.param.yaml @@ -12,6 +12,9 @@ curvature_smoothing_num_traj: 15 # point-to-point index distance used in curvature calculation (for trajectory): curvature is calculated from three points p(i-num), p(i), p(i+num) curvature_smoothing_num_ref_steer: 15 # point-to-point index distance used in curvature calculation (for steer command reference): curvature is calculated from three points p(i-num), p(i), p(i+num) + # -- trajectory extending -- + extend_trajectory_for_end_yaw_control: true # flag of trajectory extending for terminal yaw control + # -- mpc optimization -- qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or osqp) mpc_prediction_horizon: 50 # prediction horizon step From 4be7fca84db227a16e34910bcaf07b470bea04e5 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Thu, 15 Dec 2022 17:36:24 +0900 Subject: [PATCH 717/851] fix: rename use_external_emergency_stop to check_external_emergency_heartbeat (#592) * fix: rename use_external_emergency_stop to check_external_emergency_heartbeat Signed-off-by: Shumpei Wakabayashi * ci(pre-commit): autofix Signed-off-by: Shumpei Wakabayashi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- autoware_launch/launch/planning_simulator.launch.xml | 2 +- control_launch/launch/control.launch.py | 6 ++++-- control_launch/launch/control.launch.xml | 4 ++-- 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index e6bbf391a0..f3a6f78063 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -72,7 +72,7 @@ - + diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 55f159ddf3..e2c69f208d 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -168,7 +168,9 @@ def launch_setup(context, *args, **kwargs): vehicle_cmd_gate_param, { "use_emergency_handling": LaunchConfiguration("use_emergency_handling"), - "use_external_emergency_stop": LaunchConfiguration("use_external_emergency_stop"), + "check_external_emergency_heartbeat": LaunchConfiguration( + "check_external_emergency_heartbeat" + ), "use_start_request": LaunchConfiguration("use_start_request"), }, ], @@ -325,7 +327,7 @@ def add_launch_arg(name: str, default_value=None, description=None): # vehicle cmd gate add_launch_arg("use_emergency_handling", "false", "use emergency handling") - add_launch_arg("use_external_emergency_stop", "true", "use external emergency stop") + add_launch_arg("check_external_emergency_heartbeat", "true", "use external emergency stop") add_launch_arg("use_start_request", "false", "use start request service") # external cmd selector diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index ee4cd99d6e..f5d6696cc4 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -7,7 +7,7 @@ - + @@ -17,7 +17,7 @@ - + From d5759e9a937bd2d80e4e5754786a19f18108cf8e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 18 Dec 2022 13:23:35 +0900 Subject: [PATCH 718/851] feat(planning_launch): update param for cruise improvement (#614) * feat(planning_launch): update param for cruise improvement Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../obstacle_cruise_planner.param.yaml | 45 ++++++++++++++----- 1 file changed, 34 insertions(+), 11 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index ad2462c790..dfc2b2e6dd 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -4,14 +4,17 @@ planning_algorithm: "pid_base" # currently supported algorithm is "pid_base" is_showing_debug_info: false + disable_stop_planning: false # true # longitudinal info - idling_time: 1.5 # idling time to detect front vehicle starting deceleration [s] + idling_time: 2.0 # idling time to detect front vehicle starting deceleration [s] min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] safe_distance_margin : 6.0 # This is also used as a stop margin [m] terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m] + lpf_gain_for_accel: 0.2 # gain of low pass filter for ego acceleration [-] + nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index min_behavior_stop_margin: 3.0 # [m] @@ -25,7 +28,7 @@ bus: true trailer: true motorcycle: true - bicycle: false + bicycle: true pedestrian: false stop_obstacle_type: @@ -72,21 +75,41 @@ pedestrian: true pid_based_planner: - # use_predicted_obstacle_pose: false + use_velocity_limit_based_planner: true + error_function_type: quadratic # choose from linear, quadratic - # PID gains to keep safe distance with the front vehicle - kp: 2.5 - ki: 0.0 - kd: 2.3 + velocity_limit_based_planner: + # PID gains to keep safe distance with the front vehicle + kp: 10.0 + ki: 0.0 + kd: 2.0 - min_accel_during_cruise: -2.0 # minimum acceleration during cruise to slow down [m/ss] + output_ratio_during_accel: 0.6 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-] + vel_to_acc_weight: 12.0 # target acceleration is calculated by (target_velocity - current_velocity) * vel_to_acc_weight [-] + + enable_jerk_limit_to_output_acc: false + + disable_target_acceleration: true - output_ratio_during_accel: 0.6 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-] - vel_to_acc_weight: 3.0 # target acceleration is calculated by (target_velocity - current_velocity) * vel_to_acc_weight [-] + velocity_insertion_based_planner: + kp_acc: 6.0 + ki_acc: 0.0 + kd_acc: 2.0 + kp_jerk: 20.0 + ki_jerk: 0.0 + kd_jerk: 0.0 + + output_acc_ratio_during_accel: 0.6 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-] + output_jerk_ratio_during_accel: 1.0 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-] + + enable_jerk_limit_to_output_acc: true + + min_accel_during_cruise: -2.0 # minimum acceleration during cruise to slow down [m/ss] min_cruise_target_vel: 0.0 # minimum target velocity during slow down [m/s] + time_to_evaluate_rss: 0.0 - lpf_cruise_gain: 0.2 + lpf_normalized_error_cruise_dist_gain: 0.2 optimization_based_planner: dense_resampling_time_interval: 0.2 From 1fa78383d30956ebf624dec50455a1766679deba Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Sun, 18 Dec 2022 16:46:19 +0900 Subject: [PATCH 719/851] feat(planning_launch): remove unnecessary drivable area parameters (#618) Signed-off-by: yutaka Signed-off-by: yutaka --- .../behavior_path_planner/behavior_path_planner.param.yaml | 6 ------ 1 file changed, 6 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index b32e4e1b67..35137a56ce 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -8,12 +8,6 @@ minimum_lane_change_length: 12.0 minimum_pull_over_length: 16.0 - drivable_area_resolution: 0.1 - drivable_lane_forward_length: 50.0 - drivable_lane_backward_length: 5.0 - drivable_lane_margin: 1.0 - drivable_area_margin: 6.0 - refine_goal_search_radius_range: 7.5 # parameters for turn signal decider From f3a8bafd7b720cdcc798b544745811af8627fea7 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 19 Dec 2022 20:45:34 +0900 Subject: [PATCH 720/851] feat(operation_mode_transition_manager): add parameter about nearest search (#623) Signed-off-by: tomoya.kimura Signed-off-by: tomoya.kimura --- .../operation_mode_transition_manager.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml b/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml index a0ddef6e36..a86443f5ca 100644 --- a/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml +++ b/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml @@ -3,6 +3,8 @@ transition_timeout: 10.0 frequency_hz: 10.0 check_engage_condition: false # set false if you do not want to care about the engage condition. + nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index + nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index engage_acceptable_limits: allow_autonomous_in_stopped: true # no check if the velocity is zero, always allowed. dist_threshold: 1.5 From 63614a05c262e98e307dfed51d3aa0385548f1ba Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Tue, 20 Dec 2022 14:28:44 +0900 Subject: [PATCH 721/851] feat(autoware_launch): visualize multiple candidate paths (#601) * feat(autoware_launch): visualize multiple candidate paths Signed-off-by: Fumiya Watanabe * feature(autoware_launch): fix name space in autoware.rviz Signed-off-by: Fumiya Watanabe Signed-off-by: Fumiya Watanabe --- autoware_launch/rviz/autoware.rviz | 73 +++++++++++++++++++++++++++++- 1 file changed, 71 insertions(+), 2 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 36bf7252d7..be44510def 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -990,13 +990,82 @@ Visualization Manager: - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true - Name: PathChangeCandidate + Name: PathChangeCandidate_LaneChange Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/output/path_candidate + Value: /planning/path_candidate/lane_change + Value: true + View Path: + Alpha: 0.30000001192092896 + Color: 115; 210; 22 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 0.30000001192092896 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false + - Class: rviz_plugins/Path + Color Border Vel Max: 3 + Enabled: true + Name: PathChangeCandidate_Avoidance + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/path_candidate/avoidance + Value: true + View Path: + Alpha: 0.30000001192092896 + Color: 115; 210; 22 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 0.30000001192092896 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false + - Class: rviz_plugins/Path + Color Border Vel Max: 3 + Enabled: true + Name: PathChangeCandidate_PullOut + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/path_candidate/pull_out + Value: true + View Path: + Alpha: 0.30000001192092896 + Color: 115; 210; 22 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 0.30000001192092896 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false + - Class: rviz_plugins/Path + Color Border Vel Max: 3 + Enabled: true + Name: PathChangeCandidate_PullOver + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/path_candidate/pull_over Value: true View Path: Alpha: 0.30000001192092896 From 7836abd7d72a6cebf8c4216d0c2f3f446642f0bc Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 20 Dec 2022 17:34:58 +0900 Subject: [PATCH 722/851] fix(intersection): fixed stuck vehicle detection area (#624) fixed the size of stuck vehicle area Signed-off-by: Mamoru Sobue Signed-off-by: Mamoru Sobue --- .../behavior_velocity_planner/intersection.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index cd563ab9e9..f78e8b16aa 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -6,7 +6,7 @@ keep_detection_line_margin: 1.0 # distance (toward path end) from generated stop line. keep detection if ego is before this line and ego.vel < keep_detection_vel_thr keep_detection_vel_thr: 0.833 # == 3.0km/h stuck_vehicle_detect_dist: 3.0 # this should be the length between cars when they are stopped. The actual stuck vehicle detection length will be this value + vehicle_length. - stuck_vehicle_ignore_dist: 7.0 # obstacle stop max distance(5.0m) + stuck vehicle size / 2 (0.0m-) + stuck_vehicle_ignore_dist: 10.0 # obstacle stop max distance(5.0m) + stuck vehicle size / 2 (0.0m-) stuck_vehicle_vel_thr: 0.833 # 0.833m/s = 3.0km/h intersection_velocity: 2.778 # 2.778m/s = 10.0km/h intersection_max_accel: 0.5 # m/ss From acc8741d0fd5c17da27298a455e85708496335bd Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Tue, 20 Dec 2022 22:49:57 +0900 Subject: [PATCH 723/851] feat(behavior_path_planner): rename drivable area name (#628) Signed-off-by: yutaka Signed-off-by: yutaka --- .../behavior_path_planner/behavior_path_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index 35137a56ce..3423bfa221 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -19,7 +19,7 @@ path_interval: 2.0 - visualize_drivable_area_for_shared_linestrings_lanelet: true + visualize_maximum_drivable_area: true lateral_distance_max_threshold: 2.0 longitudinal_distance_min_threshold: 3.0 From e1dac8c662a848c4c2da9ccbb2d8cec3806154cf Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Wed, 21 Dec 2022 11:16:14 +0900 Subject: [PATCH 724/851] chore: sync param files (#485) Signed-off-by: GitHub Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .../component_state_monitor/topics.yaml | 2 +- .../config/system_error_monitor.param.yaml | 52 +++++++++++++++++++ .../system_monitor/cpu_monitor.param.yaml | 4 +- .../system_monitor/hdd_monitor.param.yaml | 9 ++++ .../system_monitor/net_monitor.param.yaml | 2 + 5 files changed, 66 insertions(+), 3 deletions(-) create mode 100644 system_launch/config/system_error_monitor.param.yaml diff --git a/system_launch/config/component_state_monitor/topics.yaml b/system_launch/config/component_state_monitor/topics.yaml index 5a5f2e880b..9f56c8bffe 100644 --- a/system_launch/config/component_state_monitor/topics.yaml +++ b/system_launch/config/component_state_monitor/topics.yaml @@ -82,7 +82,7 @@ args: node_name_suffix: mission_planning_route topic: /planning/mission_planning/route - topic_type: autoware_planning_msgs/msg/LaneletRoute + topic_type: autoware_auto_planning_msgs/msg/LaneletRoute best_effort: false transient_local: true warn_rate: 0.0 diff --git a/system_launch/config/system_error_monitor.param.yaml b/system_launch/config/system_error_monitor.param.yaml new file mode 100644 index 0000000000..71dc2ac600 --- /dev/null +++ b/system_launch/config/system_error_monitor.param.yaml @@ -0,0 +1,52 @@ +# Description: +# name: diag name +# sf_at: diag level where it becomes Safe Fault +# lf_at: diag level where it becomes Latent Fault +# spf_at: diag level where it becomes Single Point Fault +# auto_recovery: Determines whether the system will automatically recover when it recovers from an error. +# +# Note: +# empty-value for sf_at, lf_at and spf_at is "none" +# default values are: +# sf_at: "none" +# lf_at: "warn" +# spf_at: "error" +# auto_recovery: "true" +--- +/**: + ros__parameters: + required_modules: + autonomous_driving: + /autoware/control/autonomous_driving/node_alive_monitoring: default + /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default + /autoware/control/control_command_gate/node_alive_monitoring: default + + /autoware/localization/node_alive_monitoring: default + /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } + /autoware/localization/performance_monitoring/localization_accuracy: default + + /autoware/map/node_alive_monitoring: default + + /autoware/perception/node_alive_monitoring: default + + /autoware/planning/node_alive_monitoring: default + /autoware/planning/performance_monitoring/trajectory_validation: default + + # /autoware/sensing/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } + /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "none", spf_at: "none" } + + /autoware/vehicle/node_alive_monitoring: default + + external_control: + /autoware/control/control_command_gate/node_alive_monitoring: default + /autoware/control/external_control/external_command_selector/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } + + /autoware/vehicle/node_alive_monitoring: default diff --git a/system_launch/config/system_monitor/cpu_monitor.param.yaml b/system_launch/config/system_monitor/cpu_monitor.param.yaml index cae88d6a96..da4d74e53d 100644 --- a/system_launch/config/system_monitor/cpu_monitor.param.yaml +++ b/system_launch/config/system_monitor/cpu_monitor.param.yaml @@ -1,8 +1,8 @@ /**: ros__parameters: usage_warn: 0.96 - usage_error: 1.00 - usage_warn_count: 2 + usage_error: 0.96 + usage_warn_count: 1 usage_error_count: 2 usage_avg: true msr_reader_port: 7634 diff --git a/system_launch/config/system_monitor/hdd_monitor.param.yaml b/system_launch/config/system_monitor/hdd_monitor.param.yaml index 70f8dc5ffa..d818d848be 100644 --- a/system_launch/config/system_monitor/hdd_monitor.param.yaml +++ b/system_launch/config/system_monitor/hdd_monitor.param.yaml @@ -5,10 +5,19 @@ disks: # Until multi type lists are allowed, name N the disks as disk0...disk{N-1} disk0: name: / + temp_attribute_id: 0xC2 temp_warn: 55.0 temp_error: 70.0 + power_on_hours_attribute_id: 0x09 power_on_hours_warn: 3000000 + total_data_written_attribute_id: 0xF1 total_data_written_warn: 4915200 # =150TB (1unit=32MB) total_data_written_safety_factor: 0.05 + recovered_error_attribute_id: 0xC3 + recovered_error_warn: 1 free_warn: 5120 # MB(8hour) free_error: 100 # MB(last 1 minute) + read_data_rate_warn: 360.0 # MB/s + write_data_rate_warn: 103.5 # MB/s + read_iops_warn: 63360.0 # IOPS + write_iops_warn: 24120.0 # IOPS diff --git a/system_launch/config/system_monitor/net_monitor.param.yaml b/system_launch/config/system_monitor/net_monitor.param.yaml index 686ee349b0..cb7e1b4838 100644 --- a/system_launch/config/system_monitor/net_monitor.param.yaml +++ b/system_launch/config/system_monitor/net_monitor.param.yaml @@ -5,3 +5,5 @@ monitor_program: "greengrass" crc_error_check_duration: 1 crc_error_count_threshold: 1 + reassembles_failed_check_duration: 1 + reassembles_failed_check_count: 1 From b76d36aab74a4808b1e4f33e35e69e90f87f8710 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Wed, 21 Dec 2022 11:17:42 +0900 Subject: [PATCH 725/851] chore: update sync-param-files.yaml (#547) * chore: update sync-param-files.yaml * ci(pre-commit): autofix Co-authored-by: takayuki5168 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .github/sync-param-files.yaml | 183 +++++++++++++++++++++++++++++----- 1 file changed, 156 insertions(+), 27 deletions(-) diff --git a/.github/sync-param-files.yaml b/.github/sync-param-files.yaml index 8e6565ec96..1b18bda91c 100644 --- a/.github/sync-param-files.yaml +++ b/.github/sync-param-files.yaml @@ -1,28 +1,157 @@ -- repository: tier4/autoware.universe +- repository: autowarefoundation/autoware.universe files: - # system - ## component_state_monitor - - source: system/component_state_monitor/config/topics.yaml - dest: system_launch/config/component_state_monitor/topics.yaml - - ## system_error_monitor - - source: system/system_error_monitor/config/system_error_monitor.param.yaml - dest: system_launch/config/system_error_monitor.param.yaml - # - source: system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml - # dest: system_launch/config/system_error_monitor.planning_simulation.param.yaml - - ## system_monitor - - source: system/system_monitor/config/cpu_monitor.param.yaml - dest: system_launch/config/system_monitor/cpu_monitor.param.yaml - - source: system/system_monitor/config/gpu_monitor.param.yaml - dest: system_launch/config/system_monitor/gpu_monitor.param.yaml - - source: system/system_monitor/config/hdd_monitor.param.yaml - dest: system_launch/config/system_monitor/hdd_monitor.param.yaml - - source: system/system_monitor/config/mem_monitor.param.yaml - dest: system_launch/config/system_monitor/mem_monitor.param.yaml - - source: system/system_monitor/config/net_monitor.param.yaml - dest: system_launch/config/system_monitor/net_monitor.param.yaml - - source: system/system_monitor/config/ntp_monitor.param.yaml - dest: system_launch/config/system_monitor/ntp_monitor.param.yaml - - source: system/system_monitor/config/process_monitor.param.yaml - dest: system_launch/config/system_monitor/process_monitor.param.yaml + # tier4_autoware_api_launch + + # tier4_control_launch + - source: launch/tier4_control_launch/config/common/nearest_search.param.yaml + dest: autoware_launch/config/tier4_control_launch/common/nearest_search.param.yaml + - source: launch/tier4_control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml + dest: autoware_launch/config/tier4_control_launch/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml + - source: launch/tier4_control_launch/config/shift_decider/shift_decider.param.yaml + dest: autoware_launch/config/tier4_control_launch/shift_decider/shift_decider.param.yaml + - source: launch/tier4_control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml + dest: autoware_launch/config/tier4_control_launch/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml + - source: launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml + dest: autoware_launch/config/tier4_control_launch/trajectory_follower/longitudinal_controller.param.yaml + - source: launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml + dest: autoware_launch/config/tier4_control_launch/trajectory_follower/lateral_controller.param.yaml + - source: launch/tier4_control_launch/config/obstacle_collision_checker/obstacle_collision_checker.param.yaml + dest: autoware_launch/config/tier4_control_launch/obstacle_collision_checker/obstacle_collision_checker.param.yaml + + # tier4_localization_launch + - source: launch/tier4_localization_launch/config/ndt_scan_matcher.param.yaml + dest: autoware_launch/config/tier4_localization_launch/ndt_scan_matcher.param.yaml + - source: launch/tier4_localization_launch/config/localization_error_monitor.param.yaml + dest: autoware_launch/config/tier4_localization_launch/localization_error_monitor.param.yaml + - source: launch/tier4_localization_launch/config/random_downsample_filter.param.yaml + dest: autoware_launch/config/tier4_localization_launch/random_downsample_filter.param.yaml + - source: launch/tier4_localization_launch/config/crop_box_filter_measurement_range.param.yaml + dest: autoware_launch/config/tier4_localization_launch/crop_box_filter_measurement_range.param.yaml + - source: launch/tier4_localization_launch/config/voxel_grid_filter.param.yaml + dest: autoware_launch/config/tier4_localization_launch/voxel_grid_filter.param.yaml + + # tier4_map_launch + - source: launch/tier4_map_launch/config/pointcloud_map_loader.param.yaml + dest: autoware_launch/config/tier4_map_launch/pointcloud_map_loader.param.yaml + + # tier4_perception_launch + - source: launch/tier4_perception_launch/config/object_recognition/detection/object_position_filter.param.yaml + dest: autoware_launch/config/tier4_perception_launch/object_recognition/detection/object_position_filter.param.yaml + - source: launch/tier4_perception_launch/config/object_recognition/detection/object_lanelet_filter.param.yaml + dest: autoware_launch/config/tier4_perception_launch/object_recognition/detection/object_lanelet_filter.param.yaml + - source: launch/tier4_perception_launch/config/object_recognition/detection/pointcloud_map_filter.param.yaml + dest: autoware_launch/config/tier4_perception_launch/object_recognition/detection/pointcloud_map_filter.param.yaml + - source: launch/tier4_perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml + dest: autoware_launch/config/tier4_perception_launch/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml + - source: launch/tier4_perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml + dest: autoware_launch/config/tier4_perception_launch/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml + + # tier4_planning_launch + - source: launch/tier4_planning_launch/config/scenario_planning/common/common.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/common.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/common/nearest_search.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/nearest_search.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/common/motion_velocity_smoother/L2.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/motion_velocity_smoother/L2.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml + - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml + dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml + + # tier4_sensing_launch + + # tier4_simulator_launch + - source: launch/tier4_simulator_launch/config/fault_injection.param.yaml + dest: autoware_launch/config/tier4_simulator_launch/fault_injection.param.yaml + + # tier4_system_launch + - source: launch/tier4_system_launch/config/emergency_handler/emergency_handler.param.yaml + dest: autoware_launch/config/tier4_system_launch/emergency_handler/emergency_handler.param.yaml + - source: launch/tier4_system_launch/config/mrm_emergency_stop_operator/mrm_emergency_stop_operator.param.yaml + dest: autoware_launch/config/tier4_system_launch/mrm_emergency_stop_operator/mrm_emergency_stop_operator.param.yaml + - source: launch/tier4_system_launch/config/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator.param.yaml + dest: autoware_launch/config/tier4_system_launch/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator.param.yaml + - source: launch/tier4_system_launch/config/system_error_monitor/system_error_monitor.param.yaml + dest: autoware_launch/config/tier4_system_launch/system_error_monitor/system_error_monitor.param.yaml + - source: launch/tier4_system_launch/config/system_error_monitor/system_error_monitor.planning_simulation.param.yaml + dest: autoware_launch/config/tier4_system_launch/system_error_monitor/system_error_monitor.planning_simulation.param.yaml + - source: launch/tier4_system_launch/config/system_error_monitor/diagnostic_aggregator/vehicle.param.yaml + dest: autoware_launch/config/tier4_system_launch/system_error_monitor/diagnostic_aggregator/vehicle.param.yaml + - source: launch/tier4_system_launch/config/system_monitor/gpu_monitor.param.yaml + dest: autoware_launch/config/tier4_system_launch/system_monitor/gpu_monitor.param.yaml + - source: launch/tier4_system_launch/config/system_monitor/ntp_monitor.param.yaml + dest: autoware_launch/config/tier4_system_launch/system_monitor/ntp_monitor.param.yaml + - source: launch/tier4_system_launch/config/system_monitor/mem_monitor.param.yaml + dest: autoware_launch/config/tier4_system_launch/system_monitor/mem_monitor.param.yaml + - source: launch/tier4_system_launch/config/system_monitor/voltage_monitor.param.yaml + dest: autoware_launch/config/tier4_system_launch/system_monitor/voltage_monitor.param.yaml + - source: launch/tier4_system_launch/config/system_monitor/net_monitor.param.yaml + dest: autoware_launch/config/tier4_system_launch/system_monitor/net_monitor.param.yaml + - source: launch/tier4_system_launch/config/system_monitor/process_monitor.param.yaml + dest: autoware_launch/config/tier4_system_launch/system_monitor/process_monitor.param.yaml + - source: launch/tier4_system_launch/config/system_monitor/cpu_monitor.param.yaml + dest: autoware_launch/config/tier4_system_launch/system_monitor/cpu_monitor.param.yaml + - source: launch/tier4_system_launch/config/system_monitor/hdd_monitor.param.yaml + dest: autoware_launch/config/tier4_system_launch/system_monitor/hdd_monitor.param.yaml + + # tier4_vehicle_launch From 7cc4bab07128f63f70a8f2628564a4f54612d0dd Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 22 Dec 2022 00:23:56 +0900 Subject: [PATCH 726/851] fix(system_launch): fix topic type (#636) Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- system_launch/config/component_state_monitor/topics.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system_launch/config/component_state_monitor/topics.yaml b/system_launch/config/component_state_monitor/topics.yaml index 9f56c8bffe..5a5f2e880b 100644 --- a/system_launch/config/component_state_monitor/topics.yaml +++ b/system_launch/config/component_state_monitor/topics.yaml @@ -82,7 +82,7 @@ args: node_name_suffix: mission_planning_route topic: /planning/mission_planning/route - topic_type: autoware_auto_planning_msgs/msg/LaneletRoute + topic_type: autoware_planning_msgs/msg/LaneletRoute best_effort: false transient_local: true warn_rate: 0.0 From 03df26528bcb327780acac408ea8aedc71a0ce45 Mon Sep 17 00:00:00 2001 From: Tao Zhong <55872497+tzhong518@users.noreply.github.com> Date: Thu, 22 Dec 2022 10:11:50 +0900 Subject: [PATCH 727/851] feat(perception_launch): add launcher for pointpainting (#426) * add: launcher for pointpainting Signed-off-by: tzhong518 * fix: change perception launch Signed-off-by: tzhong518 Signed-off-by: tzhong518 Co-authored-by: Yusuke Muramatsu --- .../detection/camera_lidar_fusion_based_detection.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 eaf1dc5481..7dc95ddec4 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,7 +20,7 @@ - + From f060a104a11f390c9da9b40802a1592b417ef3ea Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Thu, 22 Dec 2022 15:07:11 +0900 Subject: [PATCH 728/851] chore: sync launch files (#622) * chore: sync launch files Signed-off-by: GitHub * revert changes * ci(pre-commit): autofix * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/planning_simulator.launch.xml * Update autoware_launch/launch/autoware.launch.xml * add rviz config * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/autoware.launch.xml * Update autoware_launch/launch/logging_simulator.launch.xml * Update autoware_launch/launch/logging_simulator.launch.xml * Update autoware_launch/launch/logging_simulator.launch.xml * Update autoware_launch/launch/logging_simulator.launch.xml * Update autoware_launch/launch/planning_simulator.launch.xml * Update autoware_launch/launch/planning_simulator.launch.xml * Update autoware_launch/launch/planning_simulator.launch.xml * Update autoware_launch/launch/planning_simulator.launch.xml * Update autoware_launch/launch/planning_simulator.launch.xml * Update autoware_launch/rviz/autoware.rviz * Update autoware_launch/rviz/autoware.rviz * Update autoware_launch/rviz/autoware.rviz * Update autoware_launch/rviz/autoware.rviz * Update autoware_launch/rviz/autoware.rviz * fix for rviz * Update autoware_launch/rviz/autoware.rviz * Update autoware_launch/rviz/autoware.rviz Signed-off-by: GitHub Co-authored-by: kminoda Co-authored-by: h-ohta Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- autoware_launch/autoware_launch.drawio.svg | 2 +- autoware_launch/launch/autoware.launch.xml | 84 ++-- .../launch/e2e_simulator.launch.xml | 65 +++ .../launch/logging_simulator.launch.xml | 156 ++---- .../launch/planning_simulator.launch.xml | 102 ++-- autoware_launch/rviz/autoware.rviz | 466 +++++++++++------- 6 files changed, 474 insertions(+), 401 deletions(-) create mode 100644 autoware_launch/launch/e2e_simulator.launch.xml diff --git a/autoware_launch/autoware_launch.drawio.svg b/autoware_launch/autoware_launch.drawio.svg index b0f7660b0b..aa1735d154 100644 --- a/autoware_launch/autoware_launch.drawio.svg +++ b/autoware_launch/autoware_launch.drawio.svg @@ -1,4 +1,4 @@ -
    autoware.launch.xml

    package: autoware_launch
    autoware.launch.xml...
    launch name

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

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

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

    package: vehicle_launch
    vehicle.launch.xml...
    system.launch.xml

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

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

    package: localization_launch
    localization.launch.xml...
    perception.launch.xml

    package: perception_launch
    perception.launch.xml...
    planning.launch.xml

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

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

    package: control_launch
    awapi_awiv_adapter.launch.xml...
    web_controller.launch.xml

    package: control_launch
    web_controller.launch.xml...
    clock_publisher.launch.xml

    package: control_launch
    clock_publisher.launch.xml...
    rviz2

    package: rviz2
    rviz2...
    planning_simulator.xml

    package: autoware_launch
    planning_simulator.xml...
    vehicle_info_launch.py

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

    package: vehicle_launch
    vehicle.launch.xml...
    system.launch.xml

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

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

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

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

    package: control_launch
    awapi_awiv_adapter.launch.xml...
    web_controller.launch.xml

    package: control_launch
    web_controller.launch.xml...
    clock_publisher.launch.xml

    package: control_launch
    clock_publisher.launch.xml...
    rviz2

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

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

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

    package: vehicle_launch
    vehicle_description.launch.xml...
    system.launch.xml

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

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

    package: perception_launch
    perception.launch.xml...
    planning.launch.xml

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

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

    package: control_launch
    web_controller.launch.xml...
    rviz2

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

    package: sensing_launch
    sensing.launch.xml...
    sensing.launch.xml

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

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

    package: simulator_launch
    simulator.launch.xml...
    simulator.launch.xml

    package: simulator_launch
    simulator.launch.xml...
    Viewer does not support full SVG 1.1
    +
    autoware.launch.xml

    package: autoware_launch
    autoware.launch.xml...
    launch name

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

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

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

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

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

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

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

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

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

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

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

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

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

    package: rviz2
    rviz2...
    planning_simulator.xml

    package: autoware_launch
    planning_simulator.xml...
    vehicle_info_launch.py

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    package: tier4_simulator_launch
    simulator.launch.xml...
    Viewer does not support full SVG 1.1
    \ No newline at end of file diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 105aeea3f4..a8bd3f4796 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -4,85 +4,112 @@ - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - + + + + + + - - - + + + - + - + + - + - + - + - + - + - + - + - + - + - + + - + @@ -91,10 +118,11 @@ - + - + + @@ -111,7 +139,7 @@ exec="rviz2" name="rviz2" output="screen" - args="-d $(find-pkg-share autoware_launch)/rviz/autoware.rviz -s $(find-pkg-share autoware_launch)/rviz/image/autoware.png" + args="-d $(var rviz_config) -s $(find-pkg-share autoware_launch)/rviz/image/autoware.png" if="$(var rviz)" /> diff --git a/autoware_launch/launch/e2e_simulator.launch.xml b/autoware_launch/launch/e2e_simulator.launch.xml new file mode 100644 index 0000000000..317decda57 --- /dev/null +++ b/autoware_launch/launch/e2e_simulator.launch.xml @@ -0,0 +1,65 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index d40700521b..50d7425bf0 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -1,6 +1,5 @@ - @@ -8,127 +7,58 @@ - - - - - - - - - - - - - + + + + + + + + + + - + - + + + + + + - - - - - - - - - - - - - - - - - - + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - - diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index f3a6f78063..ea118ff8ed 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -4,97 +4,54 @@ - - - + - - + + + + - - + - + - - - - - - - - + + - + + + + + + + + + + - + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - @@ -109,7 +66,6 @@ - diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index be44510def..d32fe7d3d5 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -18,15 +18,10 @@ Panels: Splitter Ratio: 0.5 - Class: tier4_localization_rviz_plugin/InitialPoseButtonPanel Name: InitialPoseButtonPanel - - Class: rviz_common/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: "" -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 + - Class: AutowareDateTimePanel + Name: AutowareDateTimePanel + - Class: rviz_plugins::AutowareStatePanel + Name: AutowareStatePanel Visualization Manager: Class: "" Displays: @@ -589,13 +584,13 @@ Visualization Manager: Position Transformer: XYZ Selectable: false Size (Pixels): 10 - Size (m): 0.02 + Size (m): 0.5 Style: Squares Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /localization/util/downsample/pointcloud Use Fixed Frame: true Use rainbow: true @@ -622,7 +617,7 @@ Visualization Manager: Position Transformer: XYZ Selectable: false Size (Pixels): 10 - Size (m): 0.02 + Size (m): 0.5 Style: Squares Topic: Depth: 5 @@ -709,160 +704,163 @@ Visualization Manager: Name: Segmentation - Class: rviz_common/Group Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/DetectedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true - Line Width: 0.03 - Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: DetectedObjects - Namespaces: {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/detection/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 - Value: true - Enabled: false - Name: Detection - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/TrackedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true - Line Width: 0.03 - Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: TrackedObjects - Namespaces: {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/tracking/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 - Value: true - Enabled: false - Name: Tracking - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/PredictedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: false - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: false - Display UUID: true - Display Velocity: true - Line Width: 0.03 - Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: PredictedObjects - Namespaces: {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 - Value: true - - Class: rviz_default_plugins/MarkerArray + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Line Width: 0.03 + Enabled: true + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: DetectedObjects + Namespaces: {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/detection/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 + Value: true Enabled: false - Name: Maneuver - Namespaces: - maneuver: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/prediction/maneuver - Value: true + Name: Detection + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/TrackedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Line Width: 0.03 + Enabled: true + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: TrackedObjects + Namespaces: {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/tracking/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 + Value: true + Enabled: false + Name: Tracking + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.999 + Color: 30; 144; 255 + CAR: + Alpha: 0.999 + Color: 30; 144; 255 + CYCLIST: + Alpha: 0.999 + Color: 119; 11; 32 + Class: autoware_auto_perception_rviz_plugin/PredictedObjects + Display 3d polygon: true + Display Label: true + Display PoseWithCovariance: false + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Line Width: 0.03 + Enabled: true + MOTORCYCLE: + Alpha: 0.999 + Color: 119; 11; 32 + Name: PredictedObjects + Namespaces: {} + PEDESTRIAN: + Alpha: 0.999 + Color: 255; 192; 203 + TRAILER: + Alpha: 0.999 + Color: 30; 144; 255 + TRUCK: + Alpha: 0.999 + Color: 30; 144; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/objects + UNKNOWN: + Alpha: 0.999 + Color: 255; 255; 255 + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Maneuver + Namespaces: {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/prediction/maneuver + Value: true + Enabled: true + Name: Prediction Enabled: true - Name: Prediction + Name: ObjectRecognition - Class: rviz_common/Group Displays: - Class: rviz_default_plugins/Image @@ -876,7 +874,7 @@ Visualization Manager: Depth: 5 Durability Policy: Volatile History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /perception/traffic_light_recognition/debug/rois Value: true - Class: rviz_default_plugins/MarkerArray @@ -887,11 +885,36 @@ Visualization Manager: Depth: 5 Durability Policy: Volatile History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers Value: true Enabled: true Name: TrafficLight + - Class: rviz_common/Group + Displays: + - Alpha: 0.5 + Class: rviz_default_plugins/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/occupancy_grid_map/map + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/occupancy_grid_map/map_updates + Use Timestamp: false + Value: true + Enabled: false + Name: OccupancyGrid Enabled: true Name: Perception - Class: rviz_common/Group @@ -1079,20 +1102,29 @@ Visualization Manager: Constant Color: false Scale: 0.30000001192092896 Value: false - - Class: rviz_default_plugins/MarkerArray + - Class: rviz_plugins/Path + Color Border Vel Max: 3 Enabled: true - Name: Bound - Namespaces: - left_bound: true - right_bound: true + Name: PathChangeCandidate_PullOver Topic: Depth: 5 Durability Policy: Volatile - Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/bound + Value: /planning/path_candidate/pull_over Value: true + View Path: + Alpha: 0.30000001192092896 + Color: 115; 210; 22 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 0.30000001192092896 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false - Class: rviz_common/Group Displays: - Class: rviz_default_plugins/MarkerArray @@ -1583,18 +1615,61 @@ Visualization Manager: Value: true Enabled: true Name: ObstacleCruise - - Class: rviz_default_plugins/MarkerArray + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: SurroundObstacleCheck + Namespaces: + {} + 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 + - Alpha: 1 + Class: rviz_default_plugins/Polygon + Color: 25; 255; 0 + Enabled: false + Name: Footprint + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint + Value: false + - Alpha: 1 + Class: rviz_default_plugins/Polygon + Color: 239; 41; 41 + Enabled: false + Name: FootprintOffset + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint_offset + Value: false + - Alpha: 1 + Class: rviz_default_plugins/Polygon + Color: 10; 21; 255 + Enabled: false + Name: FootprintRecoverOffset + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint_recover_offset + Value: false Enabled: true - Name: SurroundObstacleCheck - Namespaces: - {} - 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 + Name: SurroundObstacleChecker - Class: rviz_default_plugins/MarkerArray Enabled: true Name: ObstacleAvoidance @@ -1699,6 +1774,21 @@ Visualization Manager: Value: true Enabled: true Name: ScenarioPlanning + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: PlanningErrorMarker + Namespaces: {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /planning/planning_diagnostics/planning_error_monitor/debug/marker + Value: true + Enabled: false + Name: Diagnostic Enabled: true Name: Planning - Class: rviz_common/Group @@ -1746,7 +1836,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /control/trajectory_follower/pure_pursuit/debug/markers + Value: /control/trajectory_follower/controller_node_exe/debug/markers Value: false Enabled: true Name: Control @@ -1869,6 +1959,8 @@ Visualization Manager: X: 0 Y: 0 Window Geometry: + AutowareStatePanel: + collapsed: false Displays: collapsed: false Height: 1565 @@ -1876,7 +1968,9 @@ Window Geometry: Hide Right Dock: false Image: collapsed: false - QMainWindow State: 000000ff00000000fd000000040000000000000329000006fffc020000000cfb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b000fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000006e000001fb0000018200fffffffc00000275000002840000016c01000039fa000000000100000002fb0000000a0056006900650077007301000000000000033c0000015f00fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000000ffffffff0000010b00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610100000682000000eb0000000000000000fb0000000a0049006d0061006700650100000505000002680000002600fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de000000de00fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de000000de00ffffff000000010000015f000006fffc0200000002fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000e7a0000005afc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000e7a0000005afc0100000002fb0000000800540069006d0065010000000000000e7a0000057100fffffffb0000000800540069006d0065010000000000000450000000000000000000000b45000006ff00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 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 + RecognitionResultOnImage: + collapsed: false Selection: collapsed: false Tool Properties: From a48fd1e6b884454df69098ff825f425bf9ee1cae Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 22 Dec 2022 16:11:49 +0900 Subject: [PATCH 729/851] feat(behavior_path_planner): plan shift pull over/out on curve (#644) * feat(behavior_path_planner): plan shift pull over on curve Signed-off-by: kosuke55 * feat(behavior_path_planner): plan shift pull out on curve Signed-off-by: kosuke55 * remove pull_out_finish_judge_buffer param Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_out/pull_out.param.yaml | 3 +-- .../behavior_path_planner/pull_over/pull_over.param.yaml | 1 - 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml index 7a9a63f805..b092eb7fc8 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml @@ -5,12 +5,11 @@ th_stopped_velocity: 0.01 th_stopped_time: 1.0 collision_check_margin: 1.0 - pull_out_finish_judge_buffer: 1.0 + collision_check_distance_from_end: 1.0 # shift pull out enable_shift_pull_out: true shift_pull_out_velocity: 2.0 pull_out_sampling_num: 4 - before_pull_out_straight_distance: 0.0 minimum_shift_pull_out_distance: 20.0 maximum_lateral_jerk: 2.0 minimum_lateral_jerk: 0.5 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index 8e277959bc..75b5facaaa 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -35,7 +35,6 @@ minimum_lateral_jerk: 0.5 deceleration_interval: 15.0 after_pull_over_straight_distance: 5.0 - before_pull_over_straight_distance: 5.0 # parallel parking path enable_arc_forward_parking: true enable_arc_backward_parking: true From 207563528fbcb5525afb2fc190ef21aa5ef2d546 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Thu, 22 Dec 2022 16:57:50 +0900 Subject: [PATCH 730/851] feat(perception): change detection region (#630) * feat(perception): change detection region Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen Signed-off-by: badai-nguyen --- .../ground_segmentation/ground_segmentation.param.yaml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml b/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml index 8d56e12244..9a26840e34 100644 --- a/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml +++ b/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml @@ -7,11 +7,11 @@ common_crop_box_filter: parameters: - min_x: -50.0 - max_x: 100.0 - min_y: -50.0 - max_y: 50.0 - max_z: 2.5 # recommended 2.5 for non elevation_grid_mode + min_x: -100.0 + max_x: 150.0 + min_y: -70.0 + max_y: 70.0 + max_z: 2.5 min_z: -2.5 # recommended 0.0 for non elevation_grid_mode negative: False From 166f153e503d9ef3dc45e6c1941fb32186edf6cd Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Fri, 23 Dec 2022 11:23:09 +0900 Subject: [PATCH 731/851] feat(motion_velocity_smoother): change max_lateral_accel from 0.8 to 1.0 (#650) Signed-off-by: tomoya.kimura Signed-off-by: tomoya.kimura --- .../motion_velocity_smoother.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index a2b9255ef3..7f90e07b40 100644 --- a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -8,7 +8,7 @@ margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m] # curve parameters - max_lateral_accel: 0.8 # max lateral acceleration limit [m/ss] + max_lateral_accel: 1.0 # 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 From 04a956053bf2e2b8c16b0806ca9bc9d850d6bbcc Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 23 Dec 2022 22:11:57 +0900 Subject: [PATCH 732/851] feat(planning_launch): new lane change path generation parameters (#629) * feat(planning_launch): new lane change path generation parameters Signed-off-by: Muhammad Zulfaqar Azmi * rearrange parameters Signed-off-by: Muhammad Zulfaqar Azmi * fix parameter for stable result Signed-off-by: Muhammad Zulfaqar Azmi * Preparing for #652 Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_planner.param.yaml | 8 +++----- .../lane_change/lane_change.param.yaml | 14 ++++++++++++-- 2 files changed, 15 insertions(+), 7 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index 3423bfa221..e34fa49cba 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -2,10 +2,8 @@ ros__parameters: backward_path_length: 5.0 forward_path_length: 300.0 - backward_length_buffer_for_end_of_lane: 5.0 backward_length_buffer_for_end_of_pull_over: 5.0 backward_length_buffer_for_end_of_pull_out: 5.0 - minimum_lane_change_length: 12.0 minimum_pull_over_length: 16.0 refine_goal_search_radius_range: 7.5 @@ -23,11 +21,11 @@ lateral_distance_max_threshold: 2.0 longitudinal_distance_min_threshold: 3.0 - expected_front_deceleration: -0.5 + expected_front_deceleration: -1.0 expected_rear_deceleration: -1.0 - expected_front_deceleration_for_abort: -2.0 - expected_rear_deceleration_for_abort: -2.5 + expected_front_deceleration_for_abort: -1.0 + expected_rear_deceleration_for_abort: -2.0 rear_vehicle_reaction_time: 2.0 rear_vehicle_safety_time_margin: 2.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml index fc8b314b09..66d66fe780 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -2,16 +2,26 @@ ros__parameters: lane_change: lane_change_prepare_duration: 4.0 # [s] - lane_changing_duration: 8.0 # [s] + lane_changing_safety_check_duration: 8.0 # [s] + minimum_lane_change_prepare_distance: 2.0 # [m] + minimum_lane_change_length: 16.5 + backward_length_buffer_for_end_of_lane: 2.0 lane_change_finish_judge_buffer: 3.0 # [m] - minimum_lane_change_velocity: 5.6 # [m/s] + + double lane_changing_lateral_jerk: 0.5 + double lane_changing_lateral_acc: 0.5 + + minimum_lane_change_velocity: 2.78 # [m/s] prediction_time_resolution: 0.5 # [s] maximum_deceleration: 1.0 # [m/s2] lane_change_sampling_num: 10 + abort_lane_change_velocity_thresh: 0.5 abort_lane_change_angle_thresh: 10.0 # [deg] abort_lane_change_distance_thresh: 0.3 # [m] + prepare_phase_ignore_target_speed_thresh: 0.1 # [m/s] + enable_abort_lane_change: true enable_collision_check_at_prepare_phase: true use_predicted_path_outside_lanelet: true From 7ae682487fff95ecf0297cb90a1db3aedc941c8e Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Sat, 24 Dec 2022 14:11:52 +0900 Subject: [PATCH 733/851] feat(planning_launch): add new param for avoidance safety check (#637) Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- .../avoidance/avoidance.param.yaml | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index e698819fc9..e6461fa2b1 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -9,6 +9,8 @@ enable_avoidance_over_same_direction: true enable_avoidance_over_opposite_direction: true + enable_update_path_when_object_is_gone: false + enable_safety_check: false # For target object filtering threshold_speed_object_is_stopped: 1.0 # [m/s] @@ -22,11 +24,20 @@ object_check_shiftable_ratio: 0.6 # [-] object_check_min_road_shoulder_width: 0.5 # [m] + # For safety check + safety_check_backward_distance: 50.0 # [m] + safety_check_time_horizon: 10.0 # [s] + safety_check_idling_time: 1.5 # [s] + safety_check_accel_for_rss: 2.5 # [m/ss] + # For lateral margin object_envelope_buffer: 0.3 # [m] lateral_collision_margin: 1.0 # [m] lateral_collision_safety_buffer: 0.7 # [m] + # For longitudinal margin + longitudinal_collision_margin_buffer: 0.0 # [m] + prepare_time: 2.0 # [s] min_prepare_distance: 1.0 # [m] min_avoidance_distance: 10.0 # [m] @@ -72,3 +83,9 @@ # ---------- advanced parameters ---------- avoidance_execution_lateral_threshold: 0.499 + + target_velocity_matrix: + col_size: 4 + matrix: + [2.78, 5.56, 11.1, 13.9, # velocity [m/s] + 0.20, 0.90, 1.10, 1.20] # margin [m] From 0302028899094351752960972e8e2ac6fa06818b Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 26 Dec 2022 13:05:34 +0900 Subject: [PATCH 734/851] feat(control_launch): organize controller param yaml (#658) * feat(control_launch): organize controller param yaml Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * organize param files Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- autoware_launch/launch/autoware.launch.xml | 9 ++++++--- .../mpc.param.yaml} | 0 .../{ => lateral}/pure_pursuit.param.yaml | 0 .../pid.param.yaml} | 0 control_launch/launch/control.launch.py | 12 ++++++------ control_launch/package.xml | 3 +-- 6 files changed, 13 insertions(+), 11 deletions(-) rename control_launch/config/trajectory_follower/{mpc_follower.param.yaml => lateral/mpc.param.yaml} (100%) rename control_launch/config/trajectory_follower/{ => lateral}/pure_pursuit.param.yaml (100%) rename control_launch/config/trajectory_follower/{longitudinal_controller.param.yaml => longitudinal/pid.param.yaml} (100%) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index a8bd3f4796..e33089a5fd 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -119,9 +119,12 @@ - - - + + + + + + diff --git a/control_launch/config/trajectory_follower/mpc_follower.param.yaml b/control_launch/config/trajectory_follower/lateral/mpc.param.yaml similarity index 100% rename from control_launch/config/trajectory_follower/mpc_follower.param.yaml rename to control_launch/config/trajectory_follower/lateral/mpc.param.yaml diff --git a/control_launch/config/trajectory_follower/pure_pursuit.param.yaml b/control_launch/config/trajectory_follower/lateral/pure_pursuit.param.yaml similarity index 100% rename from control_launch/config/trajectory_follower/pure_pursuit.param.yaml rename to control_launch/config/trajectory_follower/lateral/pure_pursuit.param.yaml diff --git a/control_launch/config/trajectory_follower/longitudinal_controller.param.yaml b/control_launch/config/trajectory_follower/longitudinal/pid.param.yaml similarity index 100% rename from control_launch/config/trajectory_follower/longitudinal_controller.param.yaml rename to control_launch/config/trajectory_follower/longitudinal/pid.param.yaml diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index e2c69f208d..1962c8d520 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -61,8 +61,8 @@ def launch_setup(context, *args, **kwargs): shift_decider_param = yaml.safe_load(f)["/**"]["ros__parameters"] controller_component = ComposableNode( - package="trajectory_follower_nodes", - plugin="autoware::motion::control::trajectory_follower_nodes::Controller", + package="trajectory_follower_node", + plugin="autoware::motion::control::trajectory_follower_node::Controller", name="controller_node_exe", namespace="trajectory_follower", remappings=[ @@ -260,8 +260,8 @@ def add_launch_arg(name: str, default_value=None, description=None): # lateral controller mode add_launch_arg( "lateral_controller_mode", - "mpc_follower", - "lateral controller mode: `mpc_follower` or `pure_pursuit`", + "mpc", + "lateral controller mode: `mpc` or `pure_pursuit`", ) # longitudinal controller mode @@ -284,7 +284,7 @@ def add_launch_arg(name: str, default_value=None, description=None): "lat_controller_param_path", [ FindPackageShare("control_launch"), - "/config/trajectory_follower/mpc_follower.param.yaml", + "/config/mpc_lateral_controller/mpc_lateral_controller.param.yaml", ], "path to the parameter file of lateral controller. default is `mpc_follower`", ) @@ -292,7 +292,7 @@ def add_launch_arg(name: str, default_value=None, description=None): "lon_controller_param_path", [ FindPackageShare("control_launch"), - "/config/trajectory_follower/longitudinal_controller.param.yaml", + "/config/pid_longitudinal_controller/pid_longitudinal_controller.param.yaml", ], "path to the parameter file of longitudinal controller", ) diff --git a/control_launch/package.xml b/control_launch/package.xml index ed1180a06e..ebf76a49f8 100644 --- a/control_launch/package.xml +++ b/control_launch/package.xml @@ -14,8 +14,7 @@ external_cmd_converter lane_departure_checker shift_decider - trajectory_follower - trajectory_follower_nodes + trajectory_follower_node vehicle_cmd_gate ament_lint_auto From 094e11d3b10578cdd66d3e44c342a2924b8433b4 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 28 Dec 2022 12:11:52 +0900 Subject: [PATCH 735/851] refactor(control_launch): organize trajectory_follower_node's param (#661) * refactor(control_launch): organize trajectory_follower_node's param Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../trajectory_follower_node.param.yaml | 4 +++ control_launch/launch/control.launch.py | 32 +++++++++++++++++-- 2 files changed, 33 insertions(+), 3 deletions(-) create mode 100644 control_launch/config/trajectory_follower/trajectory_follower_node.param.yaml diff --git a/control_launch/config/trajectory_follower/trajectory_follower_node.param.yaml b/control_launch/config/trajectory_follower/trajectory_follower_node.param.yaml new file mode 100644 index 0000000000..dcd985bb4a --- /dev/null +++ b/control_launch/config/trajectory_follower/trajectory_follower_node.param.yaml @@ -0,0 +1,4 @@ +/**: + ros__parameters: + ctrl_period: 0.03 + timeout_thr_sec: 0.5 diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py index 1962c8d520..0dc4d1e836 100644 --- a/control_launch/launch/control.launch.py +++ b/control_launch/launch/control.launch.py @@ -39,6 +39,11 @@ def launch_setup(context, *args, **kwargs): lon_controller_param_path = LaunchConfiguration("lon_controller_param_path").perform(context) with open(lon_controller_param_path, "r") as f: lon_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] + trajectory_follower_node_param_path = LaunchConfiguration( + "trajectory_follower_node_param_path" + ).perform(context) + with open(trajectory_follower_node_param_path, "r") as f: + trajectory_follower_node_param = yaml.safe_load(f)["/**"]["ros__parameters"] vehicle_cmd_gate_param_path = LaunchConfiguration("vehicle_cmd_gate_param_path").perform( context ) @@ -83,6 +88,7 @@ def launch_setup(context, *args, **kwargs): "longitudinal_controller_mode": LaunchConfiguration("longitudinal_controller_mode"), }, nearest_search_param, + trajectory_follower_node_param, lon_controller_param, lat_controller_param, ], @@ -208,7 +214,12 @@ def launch_setup(context, *args, **kwargs): launch_arguments=[ ("use_intra_process", LaunchConfiguration("use_intra_process")), ("target_container", "/control/control_container"), - ("initial_selector_mode", LaunchConfiguration("initial_selector_mode")), + # This is temporary uncomment. I will replace control_launch with tier4_control_launch soon. + # ("initial_selector_mode", LaunchConfiguration("initial_selector_mode")), + ( + "external_cmd_selector_param_path", + LaunchConfiguration("external_cmd_selector_param_path"), + ), ], ) @@ -284,7 +295,7 @@ def add_launch_arg(name: str, default_value=None, description=None): "lat_controller_param_path", [ FindPackageShare("control_launch"), - "/config/mpc_lateral_controller/mpc_lateral_controller.param.yaml", + "/config/trajectory_follower/lateral/mpc.param.yaml", ], "path to the parameter file of lateral controller. default is `mpc_follower`", ) @@ -292,7 +303,15 @@ def add_launch_arg(name: str, default_value=None, description=None): "lon_controller_param_path", [ FindPackageShare("control_launch"), - "/config/pid_longitudinal_controller/pid_longitudinal_controller.param.yaml", + "/config/trajectory_follower/longitudinal/pid.param.yaml", + ], + "path to the parameter file of longitudinal controller", + ) + add_launch_arg( + "trajectory_follower_node_param_path", + [ + FindPackageShare("control_launch"), + "/config/trajectory_follower/trajectory_follower_node.param.yaml", ], "path to the parameter file of longitudinal controller", ) @@ -332,6 +351,13 @@ def add_launch_arg(name: str, default_value=None, description=None): # external cmd selector add_launch_arg("initial_selector_mode", "remote", "local or remote") + add_launch_arg( + "external_cmd_selector_param_path", + [ + FindPackageShare("external_cmd_selector"), + "/config/external_cmd_selector.param.yaml", + ], + ) # component add_launch_arg("use_intra_process", "false", "use ROS2 component container communication") From 9078519ec52b6111d85986e96d77d29c5c4fa73a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 28 Dec 2022 13:17:34 +0900 Subject: [PATCH 736/851] feat(behavior_path_planner): update pull over params (#666) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_over/pull_over.param.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index 75b5facaaa..5f6ebd2eec 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: pull_over: - request_length: 200.0 + request_length: 100.0 th_arrived_distance: 1.0 th_stopped_velocity: 0.01 th_stopped_time: 2.0 # It must be greater than the state_machine's. @@ -34,7 +34,7 @@ maximum_lateral_jerk: 2.0 minimum_lateral_jerk: 0.5 deceleration_interval: 15.0 - after_pull_over_straight_distance: 5.0 + after_pull_over_straight_distance: 1.0 # parallel parking path enable_arc_forward_parking: true enable_arc_backward_parking: true From 6a107493e1daf17fa37384117c3adcebaa443350 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 28 Dec 2022 13:22:17 +0900 Subject: [PATCH 737/851] fix(control_launch): add missin param in yaml (#665) Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml b/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml index 4876699351..351ad877e1 100644 --- a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml +++ b/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml @@ -12,9 +12,11 @@ lon_jerk_lim: 5.0 lat_acc_lim: 5.0 lat_jerk_lim: 5.0 + actual_steer_diff_lim: 1.0 on_transition: vel_lim: 50.0 lon_acc_lim: 1.0 lon_jerk_lim: 0.5 lat_acc_lim: 1.2 lat_jerk_lim: 0.75 + actual_steer_diff_lim: 0.05 From 5895271713b1ce04233e4ea72f4ddfad1a02c917 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 29 Dec 2022 15:38:26 +0900 Subject: [PATCH 738/851] feat(behavior_path_planner): change pull over max_lateral_offset (#670) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_over/pull_over.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index 5f6ebd2eec..4c9f4fd41b 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -17,7 +17,7 @@ backward_goal_search_length: 20.0 goal_search_interval: 2.0 longitudinal_margin: 3.0 - max_lateral_offset: 1.0 + max_lateral_offset: 0.5 lateral_offset_interval: 0.25 # occupancy grid map use_occupancy_grid: true From 3342ed48b764bb00bc87bfcc5dc8ed7a7061e59b Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 5 Jan 2023 14:15:52 +0900 Subject: [PATCH 739/851] feat(planning_launch): lane change abort parameters (#583) * feat(planning_launch): lane change abort parameters Signed-off-by: Muhammad Zulfaqar Azmi * allow very high lateral jerk for now Signed-off-by: Muhammad Zulfaqar Azmi * remove unnecessary parameter Signed-off-by: Muhammad Zulfaqar Azmi * set abort to false Signed-off-by: Muhammad Zulfaqar Azmi * fix parameter Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi --- .../lane_change/lane_change.param.yaml | 21 ++++++++++++------- 1 file changed, 13 insertions(+), 8 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml index 66d66fe780..891e54a544 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -9,21 +9,26 @@ backward_length_buffer_for_end_of_lane: 2.0 lane_change_finish_judge_buffer: 3.0 # [m] - double lane_changing_lateral_jerk: 0.5 - double lane_changing_lateral_acc: 0.5 + lane_changing_lateral_jerk: 0.5 # [m/s3] + lane_changing_lateral_acc: 0.5 # [m/s2] minimum_lane_change_velocity: 2.78 # [m/s] prediction_time_resolution: 0.5 # [s] maximum_deceleration: 1.0 # [m/s2] lane_change_sampling_num: 10 - abort_lane_change_velocity_thresh: 0.5 - abort_lane_change_angle_thresh: 10.0 # [deg] - abort_lane_change_distance_thresh: 0.3 # [m] - prepare_phase_ignore_target_speed_thresh: 0.1 # [m/s] - - enable_abort_lane_change: true + # collision check enable_collision_check_at_prepare_phase: true + prepare_phase_ignore_target_speed_thresh: 0.1 # [m/s] use_predicted_path_outside_lanelet: true use_all_predicted_path: false + + # abort + enable_cancel_lane_change: true + enable_abort_lane_change: false + + abort_delta_time: 3.0 # [s] + abort_max_lateral_jerk: 1000.0 # [m/s3] + + # debug publish_debug_marker: false From f7c7bad092e09f421e16890e3d4301734c082daa Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 5 Jan 2023 18:22:16 +0900 Subject: [PATCH 740/851] fix(planning_launch): ignore unavoidable objects around the goal (#676) * fix(planning_launch): ignore unavoidable objects around the goal Signed-off-by: satoshi-ota * Update planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml Signed-off-by: satoshi-ota Co-authored-by: Kosuke Takeuchi --- .../behavior_path_planner/avoidance/avoidance.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index e6461fa2b1..3af3a26836 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -18,6 +18,7 @@ object_check_forward_distance: 150.0 # [m] object_check_backward_distance: 2.0 # [m] + object_check_goal_distance: 20.0 # [m] threshold_distance_object_is_on_center: 1.0 # [m] From 620625bd95187c369679dc3f9430c159dbcb70b3 Mon Sep 17 00:00:00 2001 From: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Date: Thu, 5 Jan 2023 19:24:57 +0900 Subject: [PATCH 741/851] fix(behavior_velocity_planner): fix blind spot over-detection (#677) Signed-off-by: 1222-takeshi Signed-off-by: 1222-takeshi --- .../behavior_velocity_planner/blind_spot.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml index 31f75d7f7c..5af1c99f8a 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml @@ -6,3 +6,4 @@ backward_length: 15.0 # [m] ignore_width_from_center_line: 0.7 # [m] max_future_movement_time: 10.0 # [second] + threshold_yaw_diff: 0.523 # [rad] From 0b36fb959b228f4055cf95c3723ca00f97bafb6e Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 12 Jan 2023 09:24:03 +0900 Subject: [PATCH 742/851] feat(planning_launch): add new param for yield maneuver in avoidance.param.yaml (#657) * feat(planning_launch): update avoidance param Signed-off-by: satoshi-ota * fix(avoidance): fix param name for readability Signed-off-by: satoshi-ota * fix(planning_launch): add missing param Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- .../avoidance/avoidance.param.yaml | 150 ++++++++++-------- 1 file changed, 85 insertions(+), 65 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index 3af3a26836..40de19bd6c 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -2,75 +2,26 @@ /**: ros__parameters: avoidance: - resample_interval_for_planning: 0.3 - resample_interval_for_output: 4.0 - detection_area_right_expand_dist: 0.0 - detection_area_left_expand_dist: 1.0 - + resample_interval_for_planning: 0.3 # [m] + resample_interval_for_output: 4.0 # [m] + detection_area_right_expand_dist: 0.0 # [m] + detection_area_left_expand_dist: 1.0 # [m] + drivable_area_right_bound_offset: 0.0 # [m] + drivable_area_left_bound_offset: 0.0 # [m] + object_envelope_buffer: 0.3 # [m] + + # avoidance module common setting + enable_bound_clipping: false enable_avoidance_over_same_direction: true enable_avoidance_over_opposite_direction: true enable_update_path_when_object_is_gone: false enable_safety_check: false - - # For target object filtering - threshold_speed_object_is_stopped: 1.0 # [m/s] - threshold_time_object_is_moving: 1.0 # [s] - - object_check_forward_distance: 150.0 # [m] - object_check_backward_distance: 2.0 # [m] - object_check_goal_distance: 20.0 # [m] - - threshold_distance_object_is_on_center: 1.0 # [m] - - object_check_shiftable_ratio: 0.6 # [-] - object_check_min_road_shoulder_width: 0.5 # [m] - - # For safety check - safety_check_backward_distance: 50.0 # [m] - safety_check_time_horizon: 10.0 # [s] - safety_check_idling_time: 1.5 # [s] - safety_check_accel_for_rss: 2.5 # [m/ss] - - # For lateral margin - object_envelope_buffer: 0.3 # [m] - lateral_collision_margin: 1.0 # [m] - lateral_collision_safety_buffer: 0.7 # [m] - - # For longitudinal margin - longitudinal_collision_margin_buffer: 0.0 # [m] - - prepare_time: 2.0 # [s] - min_prepare_distance: 1.0 # [m] - min_avoidance_distance: 10.0 # [m] - - min_nominal_avoidance_speed: 7.0 # [m/s] - min_sharp_avoidance_speed: 1.0 # [m/s] - - road_shoulder_safety_margin: 0.0 # [m] - - max_right_shift_length: 5.0 - max_left_shift_length: 5.0 - - nominal_lateral_jerk: 0.2 # [m/s3] - max_lateral_jerk: 1.0 # [m/s3] - - object_last_seen_threshold: 2.0 - - # For prevention of large acceleration while avoidance - min_avoidance_speed_for_acc_prevention: 3.0 # [m/s] - max_avoidance_acceleration: 0.5 # [m/ss] - - # bound clipping for objects - enable_bound_clipping: false + enable_yield_maneuver: false # for debug publish_debug_marker: false print_debug_info: false - # not enabled yet - longitudinal_collision_margin_min_distance: 0.0 # [m] - longitudinal_collision_margin_time: 0.0 - # avoidance is performed for the object type with true target_object: car: true @@ -82,11 +33,80 @@ motorcycle: false pedestrian: false - # ---------- advanced parameters ---------- - avoidance_execution_lateral_threshold: 0.499 + # For target object filtering + target_filtering: + # filtering moving objects + threshold_speed_object_is_stopped: 1.0 # [m/s] + threshold_time_object_is_moving: 1.0 # [s] + # detection range + object_check_forward_distance: 150.0 # [m] + object_check_backward_distance: 2.0 # [m] + object_check_goal_distance: 20.0 # [m] + # filtering parking objects + threshold_distance_object_is_on_center: 1.0 # [m] + object_check_shiftable_ratio: 0.6 # [-] + object_check_min_road_shoulder_width: 0.5 # [m] + # lost object compensation + object_last_seen_threshold: 2.0 + + # For safety check + safety_check: + safety_check_backward_distance: 50.0 # [m] + safety_check_time_horizon: 10.0 # [s] + safety_check_idling_time: 1.5 # [s] + safety_check_accel_for_rss: 2.5 # [m/ss] + safety_check_hysteresis_factor: 2.0 # [-] + + # For avoidance maneuver + avoidance: + # avoidance lateral parameters + lateral: + lateral_collision_margin: 1.0 # [m] + lateral_collision_safety_buffer: 0.7 # [m] + lateral_passable_safety_buffer: 0.0 # [m] + road_shoulder_safety_margin: 0.0 # [m] + avoidance_execution_lateral_threshold: 0.499 + max_right_shift_length: 5.0 + max_left_shift_length: 5.0 + # avoidance distance parameters + longitudinal: + prepare_time: 2.0 # [s] + longitudinal_collision_safety_buffer: 0.0 # [m] + min_prepare_distance: 1.0 # [m] + min_avoidance_distance: 10.0 # [m] + min_nominal_avoidance_speed: 7.0 # [m/s] + min_sharp_avoidance_speed: 1.0 # [m/s] + + # For yield maneuver + yield: + yield_velocity: 2.78 # [m/s] + + # For stop maneuver + stop: + min_distance: 10.0 # [m] + max_distance: 20.0 # [m] + + constraints: + # vehicle slows down under longitudinal constraints + use_constraints_for_decel: false # [-] + + # lateral constraints + lateral: + nominal_lateral_jerk: 0.2 # [m/s3] + max_lateral_jerk: 1.0 # [m/s3] + + # longitudinal constraints + longitudinal: + nominal_deceleration: -1.0 # [m/ss] + nominal_jerk: 0.5 # [m/sss] + max_deceleration: -2.0 # [m/ss] + max_jerk: 1.0 + # For prevention of large acceleration while avoidance + min_avoidance_speed_for_acc_prevention: 3.0 # [m/s] + max_avoidance_acceleration: 0.5 # [m/ss] target_velocity_matrix: - col_size: 4 + col_size: 2 matrix: - [2.78, 5.56, 11.1, 13.9, # velocity [m/s] - 0.20, 0.90, 1.10, 1.20] # margin [m] + [2.78, 13.9, # velocity [m/s] + 0.50, 1.00] # margin [m] From 3ef3d29cbed8442daab7bb79516ab161f5dd00ca Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 13 Jan 2023 09:35:16 +0900 Subject: [PATCH 743/851] feat(behavior_path_planner): add types to skip in drivable_area_expansion params (#687) Signed-off-by: Maxime CLEMENT --- .../drivable_area_expansion.param.yaml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml index 660a4d2af0..29d577a7ad 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml @@ -3,18 +3,24 @@ avoidance: drivable_area_right_bound_offset: 0.0 drivable_area_left_bound_offset: 0.0 + drivable_area_types_to_skip: [road_border] lane_change: drivable_area_right_bound_offset: 0.0 drivable_area_left_bound_offset: 0.0 + drivable_area_types_to_skip: [road_border] lane_following: drivable_area_right_bound_offset: 0.0 drivable_area_left_bound_offset: 0.0 + drivable_area_types_to_skip: [road_border] pull_out: drivable_area_right_bound_offset: 0.0 drivable_area_left_bound_offset: 0.0 + drivable_area_types_to_skip: [road_border] pull_over: drivable_area_right_bound_offset: 0.0 drivable_area_left_bound_offset: 0.0 + drivable_area_types_to_skip: [road_border] side_shift: drivable_area_right_bound_offset: 0.0 drivable_area_left_bound_offset: 0.0 + drivable_area_types_to_skip: [road_border] From 90f77432c4f5c51ee197a11deb900dab4cf275a0 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Fri, 13 Jan 2023 20:09:40 +0900 Subject: [PATCH 744/851] feat: remove overlap with tier4_autoware_api_launch (#589) * feat: remove overlap with tier4_autoware_api_launch Signed-off-by: Takagi, Isamu * fix: merge Signed-off-by: Takagi, Isamu * fix: merge Signed-off-by: Takagi, Isamu * fix: merge Signed-off-by: Takagi, Isamu * feat: move launch files Signed-off-by: Takagi, Isamu Signed-off-by: Takagi, Isamu Co-authored-by: Hiroki OTA --- .../launch/autoware_api.launch.xml | 39 ++---------- .../include/external_api_adaptor.launch.py | 60 ------------------- .../include/internal_api_adaptor.launch.py | 44 -------------- .../include/internal_api_relay.launch.xml | 20 ------- autoware_launch/launch/autoware.launch.xml | 15 +---- 5 files changed, 8 insertions(+), 170 deletions(-) delete mode 100644 autoware_api_launch/launch/include/external_api_adaptor.launch.py delete mode 100644 autoware_api_launch/launch/include/internal_api_adaptor.launch.py delete mode 100644 autoware_api_launch/launch/include/internal_api_relay.launch.xml diff --git a/autoware_api_launch/launch/autoware_api.launch.xml b/autoware_api_launch/launch/autoware_api.launch.xml index 509e0c4f9c..ccc1527fb0 100644 --- a/autoware_api_launch/launch/autoware_api.launch.xml +++ b/autoware_api_launch/launch/autoware_api.launch.xml @@ -1,38 +1,9 @@ - - - - - - - - - - - - - - - - - - - - - - - - + + + + - - + - - - - - - - - diff --git a/autoware_api_launch/launch/include/external_api_adaptor.launch.py b/autoware_api_launch/launch/include/external_api_adaptor.launch.py deleted file mode 100644 index 3aafd3d1bb..0000000000 --- a/autoware_api_launch/launch/include/external_api_adaptor.launch.py +++ /dev/null @@ -1,60 +0,0 @@ -# Copyright 2021 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import launch -from launch_ros.actions import ComposableNodeContainer -from launch_ros.descriptions import ComposableNode - - -def _create_api_node(node_name, class_name, **kwargs): - return ComposableNode( - namespace="external", - name=node_name, - package="autoware_iv_external_api_adaptor", - plugin="external_api::" + class_name, - **kwargs - ) - - -def generate_launch_description(): - components = [ - _create_api_node("calibration_status", "CalibrationStatus"), - _create_api_node("cpu_usage", "CpuUsage"), - _create_api_node("diagnostics", "Diagnostics"), - _create_api_node("door", "Door"), - _create_api_node("emergency", "Emergency"), - _create_api_node("engage", "Engage"), - _create_api_node("fail_safe_state", "FailSafeState"), - _create_api_node("initial_pose", "InitialPose"), - _create_api_node("localization_score", "LocalizationScore"), - _create_api_node("map", "Map"), - _create_api_node("operator", "Operator"), - _create_api_node("metadata_packages", "MetadataPackages"), - _create_api_node("route", "Route"), - _create_api_node("rtc_controller", "RTCController"), - _create_api_node("service", "Service"), - _create_api_node("start", "Start"), - _create_api_node("vehicle_status", "VehicleStatus"), - _create_api_node("velocity", "Velocity"), - _create_api_node("version", "Version"), - ] - container = ComposableNodeContainer( - namespace="external", - name="autoware_iv_adaptor", - package="rclcpp_components", - executable="component_container_mt", - composable_node_descriptions=components, - output="screen", - ) - return launch.LaunchDescription([container]) diff --git a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py deleted file mode 100644 index f1962908c8..0000000000 --- a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py +++ /dev/null @@ -1,44 +0,0 @@ -# Copyright 2021 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import launch -from launch_ros.actions import ComposableNodeContainer -from launch_ros.descriptions import ComposableNode - - -def _create_api_node(node_name, class_name, **kwargs): - return ComposableNode( - namespace="internal", - name=node_name, - package="autoware_iv_internal_api_adaptor", - plugin="internal_api::" + class_name, - **kwargs - ) - - -def generate_launch_description(): - components = [ - _create_api_node("iv_msgs", "IVMsgs"), - _create_api_node("operator", "Operator"), - _create_api_node("velocity", "Velocity"), - ] - container = ComposableNodeContainer( - namespace="internal", - name="autoware_iv_adaptor", - package="rclcpp_components", - executable="component_container_mt", - composable_node_descriptions=components, - output="screen", - ) - return launch.LaunchDescription([container]) diff --git a/autoware_api_launch/launch/include/internal_api_relay.launch.xml b/autoware_api_launch/launch/include/internal_api_relay.launch.xml deleted file mode 100644 index e850fb3dc4..0000000000 --- a/autoware_api_launch/launch/include/internal_api_relay.launch.xml +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index e33089a5fd..00ea708b96 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -134,17 +134,8 @@ - - - - - + + + From 719dd857a1f2f1d260352f3164a54892ff1678d0 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 16 Jan 2023 10:55:25 +0900 Subject: [PATCH 745/851] feat(perception_launch): replace perception_launch with tier4_perception_launch (#681) * feat(perception_launch): replace perception_launch with tier4_perception_launch Signed-off-by: kminoda * fix default perception mode * Update readme * remove perception_launch from packages.xml Signed-off-by: kminoda --- README.md | 1 - autoware_launch/CMakeLists.txt | 1 + .../object_lanelet_filter.param.yaml | 0 .../object_position_filter.param.yaml | 0 .../pointcloud_map_filter.param.yaml | 0 .../data_association_matrix.param.yaml | 0 .../elevation_map_parameters.yaml | 0 .../ground_segmentation.param.yaml | 0 autoware_launch/launch/autoware.launch.xml | 5 +- .../tier4_perception_component.launch.xml | 41 ++ autoware_launch/package.xml | 1 - perception_launch/CMakeLists.txt | 16 - perception_launch/README.md | 20 - ...ra_lidar_fusion_based_detection.launch.xml | 278 --------- ...ar_radar_fusion_based_detection.launch.xml | 76 --- .../detection/detection.launch.xml | 122 ---- .../lidar_based_detection.launch.xml | 147 ----- .../lidar_radar_based_detection.launch.xml | 40 -- .../detection/pointcloud_map_filter.launch.py | 168 ------ .../radar_based_detection.launch.xml | 12 - .../prediction/prediction.launch.xml | 14 - .../tracking/tracking.launch.xml | 13 - .../ground_segmentation.launch.py | 539 ------------------ ...serscan_based_occupancy_grid_map.launch.py | 138 ----- ...ntcloud_based_occupancy_grid_map.launch.py | 92 --- .../launch/perception.launch.xml | 131 ----- .../traffic_light.launch.xml | 47 -- .../traffic_light_node_container.launch.py | 252 -------- perception_launch/package.xml | 44 -- .../perception_launch.drawio.svg | 309 ---------- 30 files changed, 45 insertions(+), 2462 deletions(-) rename {perception_launch/config => autoware_launch/config/perception}/object_recognition/detection/object_lanelet_filter.param.yaml (100%) rename {perception_launch/config => autoware_launch/config/perception}/object_recognition/detection/object_position_filter.param.yaml (100%) rename {perception_launch/config => autoware_launch/config/perception}/object_recognition/detection/pointcloud_map_filter.param.yaml (100%) rename {perception_launch/config => autoware_launch/config/perception}/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml (100%) rename {perception_launch/config => autoware_launch/config/perception}/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml (100%) rename {perception_launch/config => autoware_launch/config/perception}/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml (100%) create mode 100644 autoware_launch/launch/components/tier4_perception_component.launch.xml delete mode 100644 perception_launch/CMakeLists.txt delete mode 100644 perception_launch/README.md delete mode 100644 perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml delete mode 100644 perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml delete mode 100644 perception_launch/launch/object_recognition/detection/detection.launch.xml delete mode 100644 perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml delete mode 100644 perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml delete mode 100644 perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py delete mode 100644 perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml delete mode 100644 perception_launch/launch/object_recognition/prediction/prediction.launch.xml delete mode 100644 perception_launch/launch/object_recognition/tracking/tracking.launch.xml delete mode 100644 perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py delete mode 100644 perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py delete mode 100644 perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py delete mode 100644 perception_launch/launch/perception.launch.xml delete mode 100644 perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml delete mode 100644 perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py delete mode 100644 perception_launch/package.xml delete mode 100644 perception_launch/perception_launch.drawio.svg diff --git a/README.md b/README.md index c88abfc7f8..2e4b5af383 100644 --- a/README.md +++ b/README.md @@ -20,6 +20,5 @@ ros2 launch autoware_launch planning_simulator.launch.xml map_path:=/path/to/map - [control_launch](./control_launch) - [integration_launch](./integration_launch) - [localization_launch](./localization_launch) -- [perception_launch](./perception_launch) - [planning_launch](./planning_launch) - [system_launch](./system_launch) diff --git a/autoware_launch/CMakeLists.txt b/autoware_launch/CMakeLists.txt index 60e4e952cb..e7a67c79a1 100644 --- a/autoware_launch/CMakeLists.txt +++ b/autoware_launch/CMakeLists.txt @@ -11,6 +11,7 @@ endif() ament_auto_package( INSTALL_TO_SHARE + config launch rviz ) diff --git a/perception_launch/config/object_recognition/detection/object_lanelet_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_lanelet_filter.param.yaml similarity index 100% rename from perception_launch/config/object_recognition/detection/object_lanelet_filter.param.yaml rename to autoware_launch/config/perception/object_recognition/detection/object_lanelet_filter.param.yaml diff --git a/perception_launch/config/object_recognition/detection/object_position_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_position_filter.param.yaml similarity index 100% rename from perception_launch/config/object_recognition/detection/object_position_filter.param.yaml rename to autoware_launch/config/perception/object_recognition/detection/object_position_filter.param.yaml diff --git a/perception_launch/config/object_recognition/detection/pointcloud_map_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/pointcloud_map_filter.param.yaml similarity index 100% rename from perception_launch/config/object_recognition/detection/pointcloud_map_filter.param.yaml rename to autoware_launch/config/perception/object_recognition/detection/pointcloud_map_filter.param.yaml diff --git a/perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml similarity index 100% rename from perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml rename to autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml diff --git a/perception_launch/config/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml similarity index 100% rename from perception_launch/config/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml rename to autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml diff --git a/perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml similarity index 100% rename from perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml rename to autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 00ea708b96..c6d17ba038 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -100,8 +100,9 @@ - - + + + diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml new file mode 100644 index 0000000000..9d963a0c3d --- /dev/null +++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 2fa28bd87a..cde90494e0 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -14,7 +14,6 @@ control_launch global_parameter_loader localization_launch - perception_launch planning_launch python3-bson python3-tornado diff --git a/perception_launch/CMakeLists.txt b/perception_launch/CMakeLists.txt deleted file mode 100644 index ade04cfcd8..0000000000 --- a/perception_launch/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -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 - config -) diff --git a/perception_launch/README.md b/perception_launch/README.md deleted file mode 100644 index 9cc11ca6f7..0000000000 --- a/perception_launch/README.md +++ /dev/null @@ -1,20 +0,0 @@ -# perception_launch - -## Structure - -![perception_launch](./perception_launch.drawio.svg) - -## Package Dependencies - -Please see `` in `package.xml`. - -## Usage - -You can include as follows in `*.launch.xml` to use `perception.launch.xml`. - -```xml - - - - -``` 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 deleted file mode 100644 index 7dc95ddec4..0000000000 --- a/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ /dev/null @@ -1,278 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml deleted file mode 100644 index 86e37f80d4..0000000000 --- a/perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ /dev/null @@ -1,76 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/perception_launch/launch/object_recognition/detection/detection.launch.xml b/perception_launch/launch/object_recognition/detection/detection.launch.xml deleted file mode 100644 index c4a9c00e46..0000000000 --- a/perception_launch/launch/object_recognition/detection/detection.launch.xml +++ /dev/null @@ -1,122 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 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 deleted file mode 100644 index 9e772759df..0000000000 --- a/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml +++ /dev/null @@ -1,147 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml deleted file mode 100644 index 8150315c95..0000000000 --- a/perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml +++ /dev/null @@ -1,40 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py b/perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py deleted file mode 100644 index afcf9021c0..0000000000 --- a/perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py +++ /dev/null @@ -1,168 +0,0 @@ -# Copyright 2022 TIER IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -import os - -from ament_index_python.packages import get_package_share_directory -import launch -from launch.actions import DeclareLaunchArgument -from launch.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode -import yaml - - -class PointcloudMapFilterPipeline: - def __init__(self, context): - pointcloud_map_filter_param_path = os.path.join( - get_package_share_directory("perception_launch"), - "config/object_recognition/detection/pointcloud_map_filter.param.yaml", - ) - with open(pointcloud_map_filter_param_path, "r") as f: - self.pointcloud_map_filter_param = yaml.safe_load(f)["/**"]["ros__parameters"] - self.use_down_sample_filter = self.pointcloud_map_filter_param["use_down_sample_filter"] - self.voxel_size = self.pointcloud_map_filter_param["down_sample_voxel_size"] - self.distance_threshold = self.pointcloud_map_filter_param["distance_threshold"] - - def create_pipeline(self): - if self.use_down_sample_filter: - return self.create_down_sample_pipeline() - else: - return self.create_normal_pipeline() - - def create_normal_pipeline(self): - components = [] - components.append( - ComposableNode( - package="compare_map_segmentation", - plugin="compare_map_segmentation::VoxelBasedCompareMapFilterComponent", - name="voxel_based_compare_map_filter", - remappings=[ - ("input", LaunchConfiguration("input_topic")), - ("map", "/map/pointcloud_map"), - ("output", LaunchConfiguration("output_topic")), - ], - parameters=[ - { - "distance_threshold": self.distance_threshold, - } - ], - extra_arguments=[ - {"use_intra_process_comms": False}, - ], - ) - ) - return components - - def create_down_sample_pipeline(self): - components = [] - down_sample_topic = ( - "/perception/obstacle_segmentation/pointcloud_map_filtered/downsampled/pointcloud" - ) - components.append( - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", - name="voxel_grid_downsample_filter", - remappings=[ - ("input", LaunchConfiguration("input_topic")), - ("output", down_sample_topic), - ], - parameters=[ - { - "voxel_size_x": self.voxel_size, - "voxel_size_y": self.voxel_size, - "voxel_size_z": self.voxel_size, - } - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ), - ) - components.append( - ComposableNode( - package="compare_map_segmentation", - plugin="compare_map_segmentation::VoxelBasedCompareMapFilterComponent", - name="voxel_based_compare_map_filter", - remappings=[ - ("input", down_sample_topic), - ("map", "/map/pointcloud_map"), - ("output", LaunchConfiguration("output_topic")), - ], - parameters=[ - { - "distance_threshold": self.distance_threshold, - } - ], - extra_arguments=[ - {"use_intra_process_comms": False}, - ], - ) - ) - return components - - -def launch_setup(context, *args, **kwargs): - pipeline = PointcloudMapFilterPipeline(context) - components = [] - components.extend(pipeline.create_pipeline()) - individual_container = ComposableNodeContainer( - name=LaunchConfiguration("container_name"), - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=components, - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - pointcloud_container_loader = LoadComposableNodes( - composable_node_descriptions=components, - target_container=LaunchConfiguration("container_name"), - condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), - ) - return [individual_container, pointcloud_container_loader] - - -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("input_topic", "") - add_launch_arg("output_topic", "") - add_launch_arg("use_multithread", "False") - add_launch_arg("use_intra_process", "True") - add_launch_arg("use_pointcloud_container", "False") - add_launch_arg("container_name", "pointcloud_map_filter_pipeline_container") - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - return launch.LaunchDescription( - launch_arguments - + [set_container_executable, set_container_mt_executable] - + [OpaqueFunction(function=launch_setup)] - ) diff --git a/perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml deleted file mode 100644 index 21de187f12..0000000000 --- a/perception_launch/launch/object_recognition/detection/radar_based_detection.launch.xml +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - - diff --git a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml deleted file mode 100644 index fd9d1ba6f3..0000000000 --- a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - diff --git a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml deleted file mode 100644 index 65ac62ef3b..0000000000 --- a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py deleted file mode 100644 index f63af31655..0000000000 --- a/perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ /dev/null @@ -1,539 +0,0 @@ -# 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 - -from ament_index_python.packages import get_package_share_directory -import launch -from launch.actions import DeclareLaunchArgument -from launch.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch.substitutions import PathJoinSubstitution -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode -from launch_ros.substitutions import FindPackageShare -import yaml - - -class GroundSegmentationPipeline: - def __init__(self, context): - self.context = context - self.vehicle_info = self.get_vehicle_info() - ground_segmentation_param_path = os.path.join( - get_package_share_directory("perception_launch"), - "config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml", - ) - with open(ground_segmentation_param_path, "r") as f: - self.ground_segmentation_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - self.single_frame_obstacle_seg_output = ( - "/perception/obstacle_segmentation/single_frame/pointcloud_raw" - ) - self.output_topic = "/perception/obstacle_segmentation/pointcloud" - self.use_single_frame_filter = self.ground_segmentation_param["use_single_frame_filter"] - self.use_time_series_filter = self.ground_segmentation_param["use_time_series_filter"] - - def get_vehicle_info(self): - # TODO(TIER IV): Use Parameter Substitution after we drop Galactic support - # https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/substitutions/parameter.py - gp = self.context.launch_configurations.get("ros_params", {}) - if not gp: - gp = dict(self.context.launch_configurations.get("global_params", {})) - p = {} - p["vehicle_length"] = gp["front_overhang"] + gp["wheel_base"] + gp["rear_overhang"] - p["vehicle_width"] = gp["wheel_tread"] + gp["left_overhang"] + gp["right_overhang"] - p["min_longitudinal_offset"] = -gp["rear_overhang"] - p["max_longitudinal_offset"] = gp["front_overhang"] + gp["wheel_base"] - p["min_lateral_offset"] = -(gp["wheel_tread"] / 2.0 + gp["right_overhang"]) - p["max_lateral_offset"] = gp["wheel_tread"] / 2.0 + gp["left_overhang"] - p["min_height_offset"] = 0.0 - p["max_height_offset"] = gp["vehicle_height"] - return p - - def get_vehicle_mirror_info(self): - path = LaunchConfiguration("vehicle_mirror_param_file").perform(self.context) - with open(path, "r") as f: - p = yaml.safe_load(f) - return p - - def create_additional_pipeline(self, lidar_name): - components = [] - components.append( - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", - name=f"{lidar_name}_crop_box_filter", - remappings=[ - ("input", f"/sensing/lidar/{lidar_name}/outlier_filtered/pointcloud"), - ("output", f"{lidar_name}/range_cropped/pointcloud"), - ], - parameters=[ - { - "input_frame": LaunchConfiguration("base_frame"), - "output_frame": LaunchConfiguration("base_frame"), - }, - self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"], - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ) - ) - - components.append( - ComposableNode( - package="ground_segmentation", - plugin=self.ground_segmentation_param[f"{lidar_name}_ground_filter"]["plugin"], - name=f"{lidar_name}_ground_filter", - remappings=[ - ("input", f"{lidar_name}/range_cropped/pointcloud"), - ("output", f"{lidar_name}/pointcloud"), - ], - parameters=[ - self.ground_segmentation_param[f"{lidar_name}_ground_filter"]["parameters"] - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ) - ) - - return components - - def create_ransac_pipeline(self): - components = [] - components.append( - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", - name="concatenate_data", - namespace="plane_fitting", - remappings=[("output", "concatenated/pointcloud")], - parameters=[ - { - "input_topics": self.ground_segmentation_param["ransac_input_topics"], - "output_frame": LaunchConfiguration("base_frame"), - "timeout_sec": 1.0, - } - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ) - ) - - components.append( - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", - name="short_height_obstacle_detection_area_filter", - namespace="plane_fitting", - remappings=[ - ("input", "concatenated/pointcloud"), - ("output", "detection_area/pointcloud"), - ], - parameters=[ - { - "input_frame": LaunchConfiguration("base_frame"), - "output_frame": LaunchConfiguration("base_frame"), - }, - self.ground_segmentation_param["short_height_obstacle_detection_area_filter"][ - "parameters" - ], - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ) - ) - - components.append( - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::Lanelet2MapFilterComponent", - name="vector_map_filter", - namespace="plane_fitting", - remappings=[ - ("input/pointcloud", "detection_area/pointcloud"), - ("input/vector_map", "/map/vector_map"), - ("output", "vector_map_filtered/pointcloud"), - ], - parameters=[ - { - "voxel_size_x": 0.25, - "voxel_size_y": 0.25, - } - ], - # cannot use intra process because vector map filter uses transient local. - extra_arguments=[{"use_intra_process_comms": False}], - ) - ) - - components.append( - ComposableNode( - package="ground_segmentation", - plugin="ground_segmentation::RANSACGroundFilterComponent", - name="ransac_ground_filter", - namespace="plane_fitting", - remappings=[ - ("input", "vector_map_filtered/pointcloud"), - ("output", "pointcloud"), - ], - parameters=[self.ground_segmentation_param["ransac_ground_filter"]["parameters"]], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ) - ) - - return components - - def create_common_pipeline(self, input_topic, output_topic): - components = [] - components.append( - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", - name="crop_box_filter", - remappings=[ - ("input", input_topic), - ("output", "range_cropped/pointcloud"), - ], - parameters=[ - { - "input_frame": LaunchConfiguration("base_frame"), - "output_frame": LaunchConfiguration("base_frame"), - }, - self.ground_segmentation_param["common_crop_box_filter"]["parameters"], - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ) - ) - - components.append( - ComposableNode( - package="ground_segmentation", - plugin=self.ground_segmentation_param["common_ground_filter"]["plugin"], - name="common_ground_filter", - remappings=[ - ("input", "range_cropped/pointcloud"), - ("output", output_topic), - ], - parameters=[ - self.ground_segmentation_param["common_ground_filter"]["parameters"], - self.vehicle_info, - {"input_frame": "base_link"}, - {"output_frame": "base_link"}, - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ) - ) - return components - - def create_single_frame_obstacle_segmentation_components(self, input_topic, output_topic): - - additional_lidars = self.ground_segmentation_param["additional_lidars"] - use_ransac = bool(self.ground_segmentation_param["ransac_input_topics"]) - use_additional = bool(additional_lidars) - relay_topic = "all_lidars/pointcloud" - common_pipeline_output = ( - "single_frame/pointcloud" if use_additional or use_ransac else output_topic - ) - - components = self.create_common_pipeline( - input_topic=input_topic, - output_topic=common_pipeline_output, - ) - - if use_additional: - for lidar_name in additional_lidars: - components.extend(self.create_additional_pipeline(lidar_name)) - components.append( - self.get_additional_lidars_concatenated_component( - input_topics=[common_pipeline_output] - + [f"{x}/pointcloud" for x in additional_lidars], - output_topic=relay_topic if use_ransac else output_topic, - ) - ) - - if use_ransac: - components.extend(self.create_ransac_pipeline()) - components.append( - self.get_single_frame_obstacle_segmentation_concatenated_component( - input_topics=[ - "plane_fitting/pointcloud", - relay_topic if use_additional else common_pipeline_output, - ], - output_topic=output_topic, - ) - ) - - return components - - @staticmethod - def create_time_series_outlier_filter_components(input_topic, output_topic): - components = [] - components.append( - ComposableNode( - package="occupancy_grid_map_outlier_filter", - plugin="occupancy_grid_map_outlier_filter::OccupancyGridMapOutlierFilterComponent", - name="occupancy_grid_map_outlier_filter", - remappings=[ - ("~/input/occupancy_grid_map", "/perception/occupancy_grid_map/map"), - ("~/input/pointcloud", input_topic), - ("~/output/pointcloud", output_topic), - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ) - ) - - return components - - @staticmethod - def create_single_frame_outlier_filter_components(input_topic, output_topic): - components = [] - components.append( - ComposableNode( - package="elevation_map_loader", - plugin="ElevationMapLoaderNode", - name="elevation_map_loader", - namespace="elevation_map", - remappings=[ - ("output/elevation_map", "map"), - ("input/pointcloud_map", "/map/pointcloud_map"), - ("input/vector_map", "/map/vector_map"), - ], - parameters=[ - { - "use_lane_filter": False, - "use_inpaint": True, - "inpaint_radius": 1.0, - "param_file_path": PathJoinSubstitution( - [ - FindPackageShare("perception_launch"), - "config", - "obstacle_segmentation", - "ground_segmentation", - "elevation_map_parameters.yaml", - ] - ), - "elevation_map_directory": PathJoinSubstitution( - [FindPackageShare("elevation_map_loader"), "data", "elevation_maps"] - ), - "use_elevation_map_cloud_publisher": False, - } - ], - extra_arguments=[{"use_intra_process_comms": False}], - ) - ) - - components.append( - ComposableNode( - package="compare_map_segmentation", - plugin="compare_map_segmentation::CompareElevationMapFilterComponent", - name="compare_elevation_map_filter", - namespace="elevation_map", - remappings=[ - ("input", input_topic), - ("output", "map_filtered/pointcloud"), - ("input/elevation_map", "map"), - ], - parameters=[ - { - "map_frame": "map", - "map_layer_name": "elevation", - "height_diff_thresh": 0.15, - "input_frame": "map", - "output_frame": "base_link", - } - ], - extra_arguments=[ - {"use_intra_process_comms": False} - ], # can't use this with transient_local - ) - ) - - components.append( - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", - name="voxel_grid_filter", - namespace="elevation_map", - remappings=[ - ("input", "map_filtered/pointcloud"), - ("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, - } - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ) - ) - - components.append( - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::VoxelGridOutlierFilterComponent", - name="voxel_grid_outlier_filter", - namespace="elevation_map", - remappings=[ - ("input", "voxel_grid_filtered/pointcloud"), - ("output", output_topic), - ], - parameters=[ - { - "voxel_size_x": 0.4, - "voxel_size_y": 0.4, - "voxel_size_z": 100.0, - "voxel_points_threshold": 5, - } - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ) - ) - - return components - - @staticmethod - def get_additional_lidars_concatenated_component(input_topics, output_topic): - - return ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", - name="concatenate_data", - remappings=[("output", output_topic)], - parameters=[ - { - "input_topics": input_topics, - "output_frame": LaunchConfiguration("base_frame"), - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - @staticmethod - def get_single_frame_obstacle_segmentation_concatenated_component(input_topics, output_topic): - return ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", - name="concatenate_no_ground_data", - remappings=[("output", output_topic)], - parameters=[ - { - "input_topics": input_topics, - "output_frame": LaunchConfiguration("base_frame"), - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - -def launch_setup(context, *args, **kwargs): - pipeline = GroundSegmentationPipeline(context) - - components = [] - components.extend( - pipeline.create_single_frame_obstacle_segmentation_components( - input_topic=LaunchConfiguration("input/pointcloud"), - output_topic=pipeline.single_frame_obstacle_seg_output, - ) - ) - - relay_topic = "single_frame/filtered/pointcloud" - if pipeline.use_single_frame_filter: - components.extend( - pipeline.create_single_frame_outlier_filter_components( - input_topic=pipeline.single_frame_obstacle_seg_output, - output_topic=relay_topic - if pipeline.use_time_series_filter - else pipeline.output_topic, - context=context, - ) - ) - if pipeline.use_time_series_filter: - components.extend( - pipeline.create_time_series_outlier_filter_components( - input_topic=relay_topic - if pipeline.use_single_frame_filter - else pipeline.single_frame_obstacle_seg_output, - output_topic=pipeline.output_topic, - ) - ) - individual_container = ComposableNodeContainer( - name=LaunchConfiguration("container_name"), - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=components, - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - pointcloud_container_loader = LoadComposableNodes( - composable_node_descriptions=components, - target_container=LaunchConfiguration("container_name"), - condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), - ) - return [individual_container, pointcloud_container_loader] - - -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("use_multithread", "False") - add_launch_arg("use_intra_process", "True") - add_launch_arg("use_pointcloud_container", "False") - add_launch_arg("container_name", "perception_pipeline_container") - add_launch_arg("input/pointcloud", "/sensing/lidar/concatenated/pointcloud") - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - return launch.LaunchDescription( - launch_arguments - + [set_container_executable, set_container_mt_executable] - + [OpaqueFunction(function=launch_setup)] - ) diff --git a/perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py b/perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py deleted file mode 100644 index d371fa4398..0000000000 --- a/perception_launch/launch/occupancy_grid_map/laserscan_based_occupancy_grid_map.launch.py +++ /dev/null @@ -1,138 +0,0 @@ -# Copyright 2021 Tier IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode - - -def generate_launch_description(): - def add_launch_arg(name: str, default_value=None): - return DeclareLaunchArgument(name, default_value=default_value) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - composable_nodes = [ - ComposableNode( - package="pointcloud_to_laserscan", - plugin="pointcloud_to_laserscan::PointCloudToLaserScanNode", - name="pointcloud_to_laserscan_node", - remappings=[ - ("~/input/pointcloud", LaunchConfiguration("input/obstacle_pointcloud")), - ("~/output/laserscan", LaunchConfiguration("output/laserscan")), - ("~/output/pointcloud", LaunchConfiguration("output/pointcloud")), - ("~/output/ray", LaunchConfiguration("output/ray")), - ("~/output/stixel", LaunchConfiguration("output/stixel")), - ], - parameters=[ - { - "target_frame": "base_link", # Leave disabled to output scan in pointcloud frame - "transform_tolerance": 0.01, - "min_height": 0.0, - "max_height": 2.0, - "angle_min": -3.141592, # -M_PI - "angle_max": 3.141592, # M_PI - "angle_increment": 0.00349065850, # 0.20*M_PI/180.0 - "scan_time": 0.0, - "range_min": 1.0, - "range_max": 200.0, - "use_inf": True, - "inf_epsilon": 1.0, - # Concurrency level, affects number of pointclouds queued for processing - # and number of threads used - # 0 : Detect number of cores - # 1 : Single threaded - # 2->inf : Parallelism level - "concurrency_level": 1, - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ), - ComposableNode( - package="probabilistic_occupancy_grid_map", - plugin="occupancy_grid_map::LaserscanBasedOccupancyGridMapNode", - name="occupancy_grid_map_node", - remappings=[ - ("~/input/laserscan", LaunchConfiguration("output/laserscan")), - ("~/input/obstacle_pointcloud", LaunchConfiguration("input/obstacle_pointcloud")), - ("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")), - ("~/output/occupancy_grid_map", LaunchConfiguration("output")), - ], - parameters=[ - { - "map_resolution": 0.5, - "use_height_filter": True, - "input_obstacle_pointcloud": LaunchConfiguration("input_obstacle_pointcloud"), - "input_obstacle_and_raw_pointcloud": LaunchConfiguration( - "input_obstacle_and_raw_pointcloud" - ), - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ), - ] - - occupancy_grid_map_container = ComposableNodeContainer( - name=LaunchConfiguration("container_name"), - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=composable_nodes, - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - - load_composable_nodes = LoadComposableNodes( - composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration("container_name"), - condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), - ) - - return LaunchDescription( - [ - add_launch_arg("use_multithread", "false"), - add_launch_arg("use_intra_process", "false"), - add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"), - add_launch_arg("input/raw_pointcloud", "concatenated/pointcloud"), - add_launch_arg("output", "occupancy_grid"), - add_launch_arg("output/laserscan", "virtual_scan/laserscan"), - add_launch_arg("output/pointcloud", "virtual_scan/pointcloud"), - add_launch_arg("output/ray", "virtual_scan/ray"), - add_launch_arg("output/stixel", "virtual_scan/stixel"), - add_launch_arg("input_obstacle_pointcloud", "false"), - add_launch_arg("input_obstacle_and_raw_pointcloud", "true"), - add_launch_arg("use_pointcloud_container", "False"), - add_launch_arg("container_name", "occupancy_grid_map_container"), - set_container_executable, - set_container_mt_executable, - occupancy_grid_map_container, - load_composable_nodes, - ] - ) diff --git a/perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py b/perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py deleted file mode 100644 index 2feefdfb10..0000000000 --- a/perception_launch/launch/occupancy_grid_map/pointcloud_based_occupancy_grid_map.launch.py +++ /dev/null @@ -1,92 +0,0 @@ -# Copyright 2021 Tier IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode - - -def generate_launch_description(): - def add_launch_arg(name: str, default_value=None): - return DeclareLaunchArgument(name, default_value=default_value) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - composable_nodes = [ - ComposableNode( - package="probabilistic_occupancy_grid_map", - plugin="occupancy_grid_map::PointcloudBasedOccupancyGridMapNode", - name="occupancy_grid_map_node", - remappings=[ - ("~/input/obstacle_pointcloud", LaunchConfiguration("input/obstacle_pointcloud")), - ("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")), - ("~/output/occupancy_grid_map", LaunchConfiguration("output")), - ], - parameters=[ - { - "map_resolution": 0.5, - "use_height_filter": True, - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ), - ] - - occupancy_grid_map_container = ComposableNodeContainer( - name=LaunchConfiguration("container_name"), - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=composable_nodes, - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - - load_composable_nodes = LoadComposableNodes( - composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration("container_name"), - condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), - ) - - return LaunchDescription( - [ - add_launch_arg("use_multithread", "False"), - add_launch_arg("use_intra_process", "True"), - add_launch_arg("use_pointcloud_container", "False"), - add_launch_arg("container_name", "occupancy_grid_map_container"), - add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"), - add_launch_arg("input/raw_pointcloud", "concatenated/pointcloud"), - add_launch_arg("output", "occupancy_grid"), - set_container_executable, - set_container_mt_executable, - occupancy_grid_map_container, - load_composable_nodes, - ] - ) diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml deleted file mode 100644 index 91931d53b2..0000000000 --- a/perception_launch/launch/perception.launch.xml +++ /dev/null @@ -1,131 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml deleted file mode 100644 index 8d3ca7452b..0000000000 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ /dev/null @@ -1,47 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 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 deleted file mode 100644 index 8827dfbb98..0000000000 --- a/perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py +++ /dev/null @@ -1,252 +0,0 @@ -# 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 - -from ament_index_python.packages import get_package_share_directory -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode - - -def generate_launch_description(): - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None, description=None): - # a default_value of None is equivalent to not passing that kwarg at all - launch_arguments.append( - DeclareLaunchArgument(name, default_value=default_value, description=description) - ) - - 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_image_decompressor", "True") - 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") - - add_launch_arg("use_crosswalk_traffic_light_estimator", "True") - add_launch_arg("use_intra_process", "False") - add_launch_arg("use_multithread", "False") - - 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=LaunchConfiguration("container_executable"), - 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_signals", "classified/traffic_signals"), - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ), - 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"), - ("~/input/traffic_signals", "traffic_signals"), - ("~/output/image", "debug/rois"), - ("~/output/image/compressed", "debug/rois/compressed"), - ("~/output/image/compressedDepth", "debug/rois/compressedDepth"), - ("~/output/image/theora", "debug/rois/theora"), - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ), - ], - output="both", - ) - - estimator_loader = LoadComposableNodes( - composable_node_descriptions=[ - ComposableNode( - package="crosswalk_traffic_light_estimator", - plugin="traffic_light::CrosswalkTrafficLightEstimatorNode", - name="crosswalk_traffic_light_estimator", - remappings=[ - ("~/input/vector_map", "/map/vector_map"), - ("~/input/route", "/planning/mission_planning/route"), - ("~/input/classified/traffic_signals", "classified/traffic_signals"), - ("~/output/traffic_signals", "traffic_signals"), - ], - extra_arguments=[{"use_intra_process_comms": False}], - ), - ], - target_container=container, - condition=IfCondition(LaunchConfiguration("use_crosswalk_traffic_light_estimator")), - ) - - relay_loader = LoadComposableNodes( - composable_node_descriptions=[ - ComposableNode( - package="topic_tools", - plugin="topic_tools::RelayNode", - name="classified_signals_relay", - namespace="", - parameters=[ - {"input_topic": "classified/traffic_signals"}, - {"output_topic": "traffic_signals"}, - {"type": "autoware_auto_perception_msgs/msg/TrafficSignalArray"}, - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ) - ], - target_container=container, - condition=UnlessCondition(LaunchConfiguration("use_crosswalk_traffic_light_estimator")), - ) - - decompressor_loader = LoadComposableNodes( - composable_node_descriptions=[ - ComposableNode( - package="image_transport_decompressor", - plugin="image_preprocessor::ImageTransportDecompressor", - name="traffic_light_image_decompressor", - parameters=[{"encoding": "rgb8"}], - remappings=[ - ( - "~/input/compressed_image", - [LaunchConfiguration("input/image"), "/compressed"], - ), - ("~/output/raw_image", LaunchConfiguration("input/image")), - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ), - ], - target_container=container, - condition=IfCondition(LaunchConfiguration("enable_image_decompressor")), - ) - - 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") - - fine_detector_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"), - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ), - ], - target_container=container, - condition=IfCondition(LaunchConfiguration("enable_fine_detection")), - ) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - return LaunchDescription( - [ - *launch_arguments, - set_container_executable, - set_container_mt_executable, - container, - decompressor_loader, - fine_detector_loader, - estimator_loader, - relay_loader, - ] - ) diff --git a/perception_launch/package.xml b/perception_launch/package.xml deleted file mode 100644 index b593cacef6..0000000000 --- a/perception_launch/package.xml +++ /dev/null @@ -1,44 +0,0 @@ - - - - perception_launch - 0.1.0 - The perception_launch package - Yukihiro Saito - Shunsuke Miura - Apache License 2.0 - - ament_cmake_auto - - compare_map_segmentation - crosswalk_traffic_light_estimator - detected_object_feature_remover - detected_object_validation - detection_by_tracker - euclidean_cluster - ground_segmentation - image_projection_based_fusion - image_transport_decompressor - lidar_apollo_instance_segmentation - map_based_prediction - multi_object_tracker - object_merger - object_range_splitter - occupancy_grid_map_outlier_filter - pointcloud_preprocessor - pointcloud_to_laserscan - probabilistic_occupancy_grid_map - shape_estimation - tensorrt_yolo - traffic_light_classifier - traffic_light_map_based_detector - traffic_light_ssd_fine_detector - traffic_light_visualization - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/perception_launch/perception_launch.drawio.svg b/perception_launch/perception_launch.drawio.svg deleted file mode 100644 index 49bfa1f700..0000000000 --- a/perception_launch/perception_launch.drawio.svg +++ /dev/null @@ -1,309 +0,0 @@ - - - - - - - - - - - -
    -
    -
    - perception.launch.xml -
    -
    -
    - - package: perception_launch - -
    -
    -
    -
    -
    - - perception.launch.xml... - -
    -
    - - - - - - - -
    -
    -
    - True -
    -
    -
    -
    - - True - -
    -
    - - - - - - -
    -
    -
    - launch name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - launch name... - -
    -
    - - - - -
    -
    -
    - ex: -
    -
    -
    -
    - - ex: - -
    -
    - - - - -
    -
    -
    - node name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - node name... - -
    -
    - - - - -
    -
    -
    - other name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - other name... - -
    -
    - - - - -
    -
    -
    - $(var use_empty_dynamic_object_publisher) -
    -
    -
    -
    - - $(var use_empty_dynamic_object_publisher) - -
    -
    - - - - -
    -
    -
    - detection.launch.xml -
    -
    -
    - - package: perception_launch - -
    -
    -
    -
    -
    - - detection.launch.xml... - -
    -
    - - - - - -
    -
    -
    - False -
    -
    -
    -
    - - False - -
    -
    - - - - -
    -
    -
    - tracking.launch.xml -
    -
    -
    - - package: perception_launch - -
    -
    -
    -
    -
    - - tracking.launch.xml... - -
    -
    - - - - -
    -
    -
    - prediction.launch.xml -
    -
    -
    - - package: perception_launch - -
    -
    -
    -
    -
    - - prediction.launch.xml... - -
    -
    - - - - -
    -
    -
    - empty_objects_publisher -
    -
    -
    - - package: dummy_perception_publisher - -
    -
    -
    -
    -
    - - empty_objects_publisher... - -
    -
    - - - - -
    -
    -
    - traffic_light_recognition.launch.xml -
    -
    -
    - - package: perception_launch - -
    -
    -
    -
    -
    - - traffic_light_recognition.launch.xml... - -
    -
    - - -
    - - - - - Viewer does not support full SVG 1.1 - - - -
    \ No newline at end of file From c5fd2d78eeaf4fab28481d217da3452a3b928a71 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 16 Jan 2023 11:00:37 +0900 Subject: [PATCH 746/851] fix(autoware_launch): add dependency to tier4_perception_launch- (#692) * fix(autoware_launch): add dependency to tier4_perception_launch- * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- autoware_launch/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index cde90494e0..a9d0f1bbd1 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -21,6 +21,7 @@ simulator_launch system_launch tier4_map_launch + tier4_perception_launch tier4_sensing_launch tier4_vehicle_launch From 53c33656cd0f97d1671ed80a5dc427f485a0672d Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 16 Jan 2023 15:55:49 +0900 Subject: [PATCH 747/851] feat(localization_launch): replace localization_launch with tier4_localization_launch (#651) * remove localization_launch Signed-off-by: kminoda * Update readme * remove localization_launch from packages.xml * provide pointcloud_container_name, which should be customized depending on vehicles Signed-off-by: kminoda Signed-off-by: kminoda --- README.md | 1 - ...op_box_filter_measurement_range.param.yaml | 0 .../localization_error_monitor.param.yaml | 0 .../localization}/ndt_scan_matcher.param.yaml | 0 .../random_downsample_filter.param.yaml | 0 .../voxel_grid_filter.param.yaml | 0 autoware_launch/launch/autoware.launch.xml | 2 +- .../tier4_localization_component.launch.xml | 12 + autoware_launch/package.xml | 2 +- localization_launch/CMakeLists.txt | 22 - localization_launch/README.md | 26 - .../launch/localization.launch.xml | 39 -- .../localization_error_monitor.launch.xml | 7 - .../pose_estimator/pose_estimator.launch.xml | 16 - .../pose_twist_fusion_filter.launch.xml | 40 -- .../twist_estimator.launch.xml | 8 - .../launch/util/util.launch.py | 116 ---- .../launch/util/util.launch.xml | 25 - .../localization_launch.drawio.svg | 530 ------------------ localization_launch/package.xml | 28 - 20 files changed, 14 insertions(+), 860 deletions(-) rename {localization_launch/config => autoware_launch/config/localization}/crop_box_filter_measurement_range.param.yaml (100%) rename {localization_launch/config => autoware_launch/config/localization}/localization_error_monitor.param.yaml (100%) rename {localization_launch/config => autoware_launch/config/localization}/ndt_scan_matcher.param.yaml (100%) rename {localization_launch/config => autoware_launch/config/localization}/random_downsample_filter.param.yaml (100%) rename {localization_launch/config => autoware_launch/config/localization}/voxel_grid_filter.param.yaml (100%) create mode 100644 autoware_launch/launch/components/tier4_localization_component.launch.xml delete mode 100644 localization_launch/CMakeLists.txt delete mode 100644 localization_launch/README.md delete mode 100644 localization_launch/launch/localization.launch.xml delete mode 100644 localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml delete mode 100644 localization_launch/launch/pose_estimator/pose_estimator.launch.xml delete mode 100644 localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml delete mode 100644 localization_launch/launch/twist_estimator/twist_estimator.launch.xml delete mode 100644 localization_launch/launch/util/util.launch.py delete mode 100644 localization_launch/launch/util/util.launch.xml delete mode 100644 localization_launch/localization_launch.drawio.svg delete mode 100644 localization_launch/package.xml diff --git a/README.md b/README.md index 2e4b5af383..dc6f607866 100644 --- a/README.md +++ b/README.md @@ -19,6 +19,5 @@ ros2 launch autoware_launch planning_simulator.launch.xml map_path:=/path/to/map - [autoware_launch](./autoware_launch) - [control_launch](./control_launch) - [integration_launch](./integration_launch) -- [localization_launch](./localization_launch) - [planning_launch](./planning_launch) - [system_launch](./system_launch) diff --git a/localization_launch/config/crop_box_filter_measurement_range.param.yaml b/autoware_launch/config/localization/crop_box_filter_measurement_range.param.yaml similarity index 100% rename from localization_launch/config/crop_box_filter_measurement_range.param.yaml rename to autoware_launch/config/localization/crop_box_filter_measurement_range.param.yaml diff --git a/localization_launch/config/localization_error_monitor.param.yaml b/autoware_launch/config/localization/localization_error_monitor.param.yaml similarity index 100% rename from localization_launch/config/localization_error_monitor.param.yaml rename to autoware_launch/config/localization/localization_error_monitor.param.yaml diff --git a/localization_launch/config/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml similarity index 100% rename from localization_launch/config/ndt_scan_matcher.param.yaml rename to autoware_launch/config/localization/ndt_scan_matcher.param.yaml diff --git a/localization_launch/config/random_downsample_filter.param.yaml b/autoware_launch/config/localization/random_downsample_filter.param.yaml similarity index 100% rename from localization_launch/config/random_downsample_filter.param.yaml rename to autoware_launch/config/localization/random_downsample_filter.param.yaml diff --git a/localization_launch/config/voxel_grid_filter.param.yaml b/autoware_launch/config/localization/voxel_grid_filter.param.yaml similarity index 100% rename from localization_launch/config/voxel_grid_filter.param.yaml rename to autoware_launch/config/localization/voxel_grid_filter.param.yaml diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index c6d17ba038..f3d79b9963 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -95,7 +95,7 @@ - + diff --git a/autoware_launch/launch/components/tier4_localization_component.launch.xml b/autoware_launch/launch/components/tier4_localization_component.launch.xml new file mode 100644 index 0000000000..7ef5fa06fc --- /dev/null +++ b/autoware_launch/launch/components/tier4_localization_component.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index a9d0f1bbd1..76260f859c 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -13,13 +13,13 @@ autoware_api_launch control_launch global_parameter_loader - localization_launch planning_launch python3-bson python3-tornado rviz2 simulator_launch system_launch + tier4_localization_launch tier4_map_launch tier4_perception_launch tier4_sensing_launch diff --git a/localization_launch/CMakeLists.txt b/localization_launch/CMakeLists.txt deleted file mode 100644 index 9815ea4b7c..0000000000 --- a/localization_launch/CMakeLists.txt +++ /dev/null @@ -1,22 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(localization_launch) - -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() - -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 - config -) diff --git a/localization_launch/README.md b/localization_launch/README.md deleted file mode 100644 index 959768012c..0000000000 --- a/localization_launch/README.md +++ /dev/null @@ -1,26 +0,0 @@ -# localization_launch - -## Structure - -![localization_launch](./localization_launch.drawio.svg) - -## Package Dependencies - -Please see `` in `package.xml`. - -## Usage - -You can include as follows in `*.launch.xml` to use `localization.launch.xml`. - -```xml - - -``` - -## Notes - -There are some `param.yaml` files in `config` directory. - -```bash -ndt_scan_matcher.param.yaml -``` diff --git a/localization_launch/launch/localization.launch.xml b/localization_launch/launch/localization.launch.xml deleted file mode 100644 index 91fbe6ac97..0000000000 --- a/localization_launch/launch/localization.launch.xml +++ /dev/null @@ -1,39 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml b/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml deleted file mode 100644 index c895da4917..0000000000 --- a/localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml deleted file mode 100644 index 3273db453f..0000000000 --- a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - 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 deleted file mode 100644 index 3c109769e1..0000000000 --- a/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml +++ /dev/null @@ -1,40 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml deleted file mode 100644 index 155521a0ed..0000000000 --- a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - - - - - - diff --git a/localization_launch/launch/util/util.launch.py b/localization_launch/launch/util/util.launch.py deleted file mode 100644 index 1721ec7d7b..0000000000 --- a/localization_launch/launch/util/util.launch.py +++ /dev/null @@ -1,116 +0,0 @@ -# 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.actions import OpaqueFunction -from launch.conditions import LaunchConfigurationNotEquals -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode -from launch_ros.substitutions import FindPackageShare -import yaml - - -def launch_setup(context, *args, **kwargs): - # https://github.com/ros2/launch_ros/issues/156 - def load_composable_node_param(param_path): - with open(LaunchConfiguration(param_path).perform(context), "r") as f: - return yaml.safe_load(f)["/**"]["ros__parameters"] - - crop_box_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", - name="crop_box_filter_measurement_range", - remappings=[ - ("input", LaunchConfiguration("input/pointcloud")), - ("output", "measurement_range/pointcloud"), - ], - parameters=[ - load_composable_node_param("crop_box_filter_measurement_range_param_path"), - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - voxel_grid_downsample_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", - name="voxel_grid_downsample_filter", - remappings=[ - ("input", "measurement_range/pointcloud"), - ("output", "voxel_grid_downsample/pointcloud"), - ], - parameters=[load_composable_node_param("voxel_grid_downsample_filter_param_path")], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - random_downsample_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::RandomDownsampleFilterComponent", - name="random_downsample_filter", - remappings=[ - ("input", "voxel_grid_downsample/pointcloud"), - ("output", LaunchConfiguration("output/pointcloud")), - ], - parameters=[load_composable_node_param("random_downsample_filter_param_path")], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - composable_nodes = [ - crop_box_component, - voxel_grid_downsample_component, - random_downsample_component, - ] - - load_composable_nodes = LoadComposableNodes( - condition=LaunchConfigurationNotEquals("container", ""), - composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration("container"), - ) - - return [load_composable_nodes] - - -def generate_launch_description(): - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None, description=None): - arg = DeclareLaunchArgument(name, default_value=default_value, description=description) - launch_arguments.append(arg) - - add_launch_arg( - "crop_box_filter_measurement_range_param_path", - [ - FindPackageShare("localization_launch"), - "/config/crop_box_filter_measurement_range.param.yaml", - ], - "path to the parameter file of crop_box_filter_measurement_range", - ) - add_launch_arg( - "voxel_grid_downsample_filter_param_path", - [FindPackageShare("localization_launch"), "/config/voxel_grid_filter.param.yaml"], - "path to the parameter file of voxel_grid_downsample_filter", - ) - add_launch_arg( - "random_downsample_filter_param_path", - [FindPackageShare("localization_launch"), "/config/random_downsample_filter.param.yaml"], - "path to the parameter file of random_downsample_filter", - ) - add_launch_arg("use_intra_process", "true", "use ROS2 component container communication") - - add_launch_arg( - "output/pointcloud", - "downsample/pointcloud", - "final output topic name", - ) - - return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml deleted file mode 100644 index 783eee8adc..0000000000 --- a/localization_launch/launch/util/util.launch.xml +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/localization_launch/localization_launch.drawio.svg b/localization_launch/localization_launch.drawio.svg deleted file mode 100644 index 1bde302430..0000000000 --- a/localization_launch/localization_launch.drawio.svg +++ /dev/null @@ -1,530 +0,0 @@ - - - - - - - -
    -
    -
    - /sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container -
    -
    -
    - - package: rclcpp_components - -
    -
    -
    -
    -
    - - /sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container... - -
    -
    - - - - -
    -
    -
    - localization.launch.xml -
    -
    -
    - - package: localization - - - _launch - -
    -
    -
    -
    -
    - - localization.launch.xml... - -
    -
    - - - - - - - - -
    -
    -
    - util.launch.xml -
    -
    -
    - package: localization_launch -
    -
    -
    -
    -
    - - util.launch.xml... - -
    -
    - - - - - - - - -
    -
    -
    - pose_estimator.launch.xml -
    -
    -
    - - package: localization_launch - -
    -
    -
    -
    -
    - - pose_estimator.launch.xml... - -
    -
    - - - - -
    -
    -
    - launch name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - launch name... - -
    -
    - - - - -
    -
    -
    - ex: -
    -
    -
    -
    - - ex: - -
    -
    - - - - -
    -
    -
    - node name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - node name... - -
    -
    - - - - -
    -
    -
    - other name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - other name... - -
    -
    - - - - - - -
    -
    -
    - twist_estimator.launch.xml -
    -
    -
    - - package: localization_launch - -
    -
    -
    -
    -
    - - twist_estimator.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - pose_twist_fusion_filter.launch.xml -
    -
    -
    - - package: localization_launch - -
    -
    -
    -
    -
    - - pose_twist_fusion_filter.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - localization_error_monitor.launch.xml -
    -
    -
    - - package: localization_error_monitor - -
    -
    -
    -
    -
    - - localization_error_monitor.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - relay -
    -
    -
    - - package: topic_tools - -
    -
    - -
    -
    -
    -
    - - input: /localization/pose_twist_fusion_filter/twist - -
    -
    - - output: /localization/twist - -
    -
    -
    -
    -
    - - relay... - -
    -
    - - - - - - -
    -
    -
    - ndt_scan_matcher.launch.xml -
    -
    -
    - - package: ndt_scan_matcher - -
    -
    -
    -
    -
    - - ndt_scan_matcher.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - gyro_odometer.launch.xml -
    -
    -
    - - package: gyro_odometer - -
    -
    -
    -
    -
    - - gyro_odometer.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - ekf_localizer.launch.xml -
    -
    -
    - - package: ekf_localizer - -
    -
    -
    -
    -
    - - ekf_localizer.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - pose_initializer.launch.xml -
    -
    -
    - - package: pose_initializer - -
    -
    -
    -
    -
    - - pose_initializer.launch.xml... - -
    -
    - - - - -
    -
    -
    - util.launch.py -
    -
    -
    - - package: localization_launch - -
    -
    -
    -
    -
    - - util.launch.py... - -
    -
    - - - - - - -
    -
    -
    - crop_box_measurement_range -
    -
    -
    - - package: pointcloud_preprocessor - -
    -
    -
    -
    -
    - - crop_box_measurement_range... - -
    -
    - - - - -
    -
    -
    - voxel_grid_downsample_filter -
    -
    -
    - - package: pointcloud_preprocessor - -
    -
    -
    -
    -
    - - voxel_grid_downsample_filter... - -
    -
    - - - - -
    -
    -
    - random_downsample_filter -
    -
    -
    - - package: pointcloud_preprocessor - -
    -
    -
    -
    -
    - - random_downsample_filter... - -
    -
    - - -
    - - - - - Viewer does not support full SVG 1.1 - - - -
    diff --git a/localization_launch/package.xml b/localization_launch/package.xml deleted file mode 100644 index c61aaeed79..0000000000 --- a/localization_launch/package.xml +++ /dev/null @@ -1,28 +0,0 @@ - - - - localization_launch - 0.1.0 - The localization_launch package - - Yamato Ando - - Apache License 2.0 - - ament_cmake_auto - - automatic_pose_initializer - ekf_localizer - gyro_odometer - ndt_scan_matcher - pointcloud_preprocessor - pose_initializer - topic_tools - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - From f691d704fe70f28386ef295e633c48be42b2614e Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 16 Jan 2023 18:57:39 +0900 Subject: [PATCH 748/851] fix(simulator_launch): use tier4_perception_launch (#693) --- simulator_launch/launch/simulator.launch.xml | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml index 08d27a73b1..79225ea0a8 100644 --- a/simulator_launch/launch/simulator.launch.xml +++ b/simulator_launch/launch/simulator.launch.xml @@ -1,4 +1,13 @@ + + + @@ -21,7 +30,7 @@ - + @@ -47,13 +56,13 @@ - + - + @@ -71,7 +80,7 @@ - + From 860a85fa8615e4ce00b4f2afc074942a322fa009 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 17 Jan 2023 18:38:12 +0900 Subject: [PATCH 749/851] feat(behavior_path_planner): ignore pull over goal near lane start (#699) feat(behavior_path_planner) ignore pull over goal near lane start Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_over/pull_over.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index 4c9f4fd41b..f09439edf7 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -19,6 +19,7 @@ longitudinal_margin: 3.0 max_lateral_offset: 0.5 lateral_offset_interval: 0.25 + ignore_distance_from_lane_start: 15.0 # occupancy grid map use_occupancy_grid: true use_occupancy_grid_for_longitudinal_margin: false From 23d464bea75f1796b7b9b1d30af45ade26722a9a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 17 Jan 2023 21:02:00 +0900 Subject: [PATCH 750/851] feat(behavior_path_planner): add option for combining arc pull out paths (#701) * feat(behavior_path_planner): add option for combining arc pull out paths Signed-off-by: kosuke55 * divide_pull_out_path Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_out/pull_out.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml index b092eb7fc8..bde6daa42d 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml @@ -16,6 +16,7 @@ deceleration_interval: 15.0 # geometric pull out enable_geometric_pull_out: true + divide_pull_out_path: false geometric_pull_out_velocity: 1.0 arc_path_interval: 1.0 lane_departure_margin: 0.2 From 761bbf08a54cfd5702ec3dc5140f86d0578d690f Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 18 Jan 2023 11:55:13 +0900 Subject: [PATCH 751/851] feat(simulator_launch): replace with tier4_simulator_launch (#698) * fix(simulator_launch): use tier4_perception_launch Signed-off-by: kminoda * feat(simulator_launch): replace with tier4_simulator_launch Signed-off-by: kminoda * remove simulator_launch Signed-off-by: kminoda * fix dependency Signed-off-by: kminoda Signed-off-by: kminoda --- .../simulator}/fault_injection.param.yaml | 0 .../tier4_simulator_component.launch.xml | 34 +++++++++++++++++++ .../launch/planning_simulator.launch.xml | 3 +- autoware_launch/package.xml | 2 +- simulator_launch/CMakeLists.txt | 15 -------- simulator_launch/README.md | 15 -------- simulator_launch/package.xml | 23 ------------- simulator_launch/simulator_launch.drawio.svg | 4 --- 8 files changed, 37 insertions(+), 59 deletions(-) rename {simulator_launch/config => autoware_launch/config/simulator}/fault_injection.param.yaml (100%) create mode 100644 autoware_launch/launch/components/tier4_simulator_component.launch.xml delete mode 100644 simulator_launch/CMakeLists.txt delete mode 100644 simulator_launch/README.md delete mode 100644 simulator_launch/package.xml delete mode 100644 simulator_launch/simulator_launch.drawio.svg diff --git a/simulator_launch/config/fault_injection.param.yaml b/autoware_launch/config/simulator/fault_injection.param.yaml similarity index 100% rename from simulator_launch/config/fault_injection.param.yaml rename to autoware_launch/config/simulator/fault_injection.param.yaml diff --git a/autoware_launch/launch/components/tier4_simulator_component.launch.xml b/autoware_launch/launch/components/tier4_simulator_component.launch.xml new file mode 100644 index 0000000000..34b7258fbc --- /dev/null +++ b/autoware_launch/launch/components/tier4_simulator_component.launch.xml @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index ea118ff8ed..77e13311cc 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -60,7 +60,7 @@ - + @@ -69,6 +69,7 @@ +
    diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 76260f859c..07eb1b22e2 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -17,12 +17,12 @@ python3-bson python3-tornado rviz2 - simulator_launch system_launch tier4_localization_launch tier4_map_launch tier4_perception_launch tier4_sensing_launch + tier4_simulator_launch tier4_vehicle_launch ament_lint_auto diff --git a/simulator_launch/CMakeLists.txt b/simulator_launch/CMakeLists.txt deleted file mode 100644 index 05e5c27e2b..0000000000 --- a/simulator_launch/CMakeLists.txt +++ /dev/null @@ -1,15 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(simulator_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 - config -) diff --git a/simulator_launch/README.md b/simulator_launch/README.md deleted file mode 100644 index d52b6c16a6..0000000000 --- a/simulator_launch/README.md +++ /dev/null @@ -1,15 +0,0 @@ -# simulator_launch - -## Structure - -![simulator_launch](./simulator_launch.drawio.svg) - -## Package Dependencies - -Please see `` in `package.xml`. - -## Usage - -```xml - -``` diff --git a/simulator_launch/package.xml b/simulator_launch/package.xml deleted file mode 100644 index 03d415a7a8..0000000000 --- a/simulator_launch/package.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - simulator_launch - 0.1.0 - The simulator_launch package - - Keisuke Shima - Apache License 2.0 - - ament_cmake_auto - - dummy_perception_publisher - fault_injection - simple_planning_simulator - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/simulator_launch/simulator_launch.drawio.svg b/simulator_launch/simulator_launch.drawio.svg deleted file mode 100644 index d86b068066..0000000000 --- a/simulator_launch/simulator_launch.drawio.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - -
    simulator.launch.xml

    package: simulator_launch
    simulator.launch.xml...
    fault_injection.launch.xml

    package: fault_injection
    fault_injection.launch.xm...
    simple_planning_simulator.launch.xml

    package: simple_planning_simulator
    simple_planning_simulator.launch.xml...
    True
    True
    $(var vehicle_simulation)
    $(var vehicle_simulation)
    launch name

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

    package: package name
    node name...
    $(var scenario_simulation)
    $(var scenario_simulation)
    False
    False
    other name

    package: package name
    other name...
    True
    True
    $(var scenario_simulation)
    $(var scenario_simulation)
    False
    False
    dummy_perception_publisher.launch.xml

    package: dummy_perception_publisher
    dummy_perception_publisher.launch.xml...
    Viewer does not support full SVG 1.1
    \ No newline at end of file From e03d073319704c6ecb93f7718499c8d415c37be4 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 18 Jan 2023 12:58:31 +0900 Subject: [PATCH 752/851] fix(simulator_launch): completely remove simulator_launch (#706) Signed-off-by: kminoda Signed-off-by: kminoda --- simulator_launch/launch/simulator.launch.xml | 105 ------------------- 1 file changed, 105 deletions(-) delete mode 100644 simulator_launch/launch/simulator.launch.xml diff --git a/simulator_launch/launch/simulator.launch.xml b/simulator_launch/launch/simulator.launch.xml deleted file mode 100644 index 79225ea0a8..0000000000 --- a/simulator_launch/launch/simulator.launch.xml +++ /dev/null @@ -1,105 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - From 7ed8f5abdca392104bdd9e813ba9cb0c59105482 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 18 Jan 2023 16:13:06 +0900 Subject: [PATCH 753/851] feat(behavior_path_planner): ignore pull out start near lane end (#702) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_out/pull_out.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml index bde6daa42d..27c2b0c9b8 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml @@ -28,3 +28,4 @@ max_back_distance: 15.0 backward_search_resolution: 2.0 backward_path_update_duration: 3.0 + ignore_distance_from_lane_end: 15.0 From c5bed8ff35d954c6e680fd826446e05cb2f2a353 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 18 Jan 2023 20:57:47 +0900 Subject: [PATCH 754/851] feat(autoware_api_launch): remove autoware api launch (#707) * feat(autoware_api_launch): remove autoware api launch Signed-off-by: Takagi, Isamu * fix Signed-off-by: Takagi, Isamu * feat: use component style Signed-off-by: Takagi, Isamu Signed-off-by: Takagi, Isamu --- autoware_api_launch/CMakeLists.txt | 12 --------- autoware_api_launch/package.xml | 26 ------------------- autoware_launch/launch/autoware.launch.xml | 4 +-- .../tier4_autoware_api_component.launch.xml | 0 autoware_launch/package.xml | 3 ++- 5 files changed, 4 insertions(+), 41 deletions(-) delete mode 100644 autoware_api_launch/CMakeLists.txt delete mode 100644 autoware_api_launch/package.xml rename autoware_api_launch/launch/autoware_api.launch.xml => autoware_launch/launch/components/tier4_autoware_api_component.launch.xml (100%) diff --git a/autoware_api_launch/CMakeLists.txt b/autoware_api_launch/CMakeLists.txt deleted file mode 100644 index 37c18e108f..0000000000 --- a/autoware_api_launch/CMakeLists.txt +++ /dev/null @@ -1,12 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(autoware_api_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_api_launch/package.xml b/autoware_api_launch/package.xml deleted file mode 100644 index ef6f3e838a..0000000000 --- a/autoware_api_launch/package.xml +++ /dev/null @@ -1,26 +0,0 @@ - - - - autoware_api_launch - 0.0.0 - The autoware_api_launch package - Takagi, Isamu - Apache License 2.0 - - ament_cmake_auto - - autoware_iv_external_api_adaptor - autoware_iv_internal_api_adaptor - awapi_awiv_adapter - default_ad_api - path_distance_calculator - rosbridge_server - topic_tools - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index f3d79b9963..aaeaa13d39 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -130,9 +130,9 @@
    - + - + diff --git a/autoware_api_launch/launch/autoware_api.launch.xml b/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml similarity index 100% rename from autoware_api_launch/launch/autoware_api.launch.xml rename to autoware_launch/launch/components/tier4_autoware_api_component.launch.xml diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 07eb1b22e2..7b17634425 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -5,12 +5,12 @@ The autoware_launch package Yukihiro Saito + Takagi, Isamu Apache License 2.0 ament_cmake_auto ad_api_adaptors - autoware_api_launch control_launch global_parameter_loader planning_launch @@ -18,6 +18,7 @@ python3-tornado rviz2 system_launch + tier4_autoware_api_launch tier4_localization_launch tier4_map_launch tier4_perception_launch From f559bbb597ae74810ece49ce85b9858898062cc2 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 20 Jan 2023 11:46:11 +0900 Subject: [PATCH 755/851] fix(behavior_path_planner): prevent pull out back twice (#713) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_out/pull_out.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml index 27c2b0c9b8..68000747b7 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml @@ -25,7 +25,7 @@ # search start pose backward enable_back: true search_priority: "efficient_path" # "efficient_path" or "short_back_distance" - max_back_distance: 15.0 + max_back_distance: 30.0 backward_search_resolution: 2.0 backward_path_update_duration: 3.0 ignore_distance_from_lane_end: 15.0 From c192ab84d7bfd309e734939d02add1dbcd4c8f8b Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 20 Jan 2023 12:38:15 +0900 Subject: [PATCH 756/851] refactor(autoware_launch): remove control_launch, and use tier4_control_launch instead (#700) * refactor(autoware_launch): remove control_launch, and use tier4_control_launch instead Signed-off-by: Takayuki Murooka * remove control_launch Signed-off-by: Takayuki Murooka * ci(pre-commit): autofix * ci(pre-commit): autofix Signed-off-by: Takayuki Murooka Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../control}/common/nearest_search.param.yaml | 0 .../external_cmd_selector.param.yaml | 4 + .../lane_departure_checker.param.yaml | 15 + .../obstacle_collision_checker.param.yaml | 11 + ...eration_mode_transition_manager.param.yaml | 0 .../shift_decider/shift_decider.param.yaml | 0 .../lateral/mpc.param.yaml | 0 .../lateral/pure_pursuit.param.yaml | 16 + .../longitudinal/pid.param.yaml | 0 .../trajectory_follower_node.param.yaml | 0 .../vehicle_cmd_gate.param.yaml | 3 + autoware_launch/launch/autoware.launch.xml | 12 +- .../tier4_control_component.launch.xml | 45 ++ .../launch/planning_simulator.launch.xml | 2 - autoware_launch/package.xml | 2 +- control_launch/CMakeLists.txt | 23 - control_launch/README.md | 24 - .../lateral/pure_pursuit.param.yaml | 9 - control_launch/control_launch.drawio.svg | 421 ------------------ control_launch/launch/control.launch.py | 382 ---------------- control_launch/launch/control.launch.xml | 23 - control_launch/package.xml | 26 -- 22 files changed, 100 insertions(+), 918 deletions(-) rename {control_launch/config => autoware_launch/config/control}/common/nearest_search.param.yaml (100%) create mode 100644 autoware_launch/config/control/external_cmd_selector/external_cmd_selector.param.yaml create mode 100644 autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml create mode 100644 autoware_launch/config/control/obstacle_collision_checker/obstacle_collision_checker.param.yaml rename {control_launch/config => autoware_launch/config/control}/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml (100%) rename {control_launch/config => autoware_launch/config/control}/shift_decider/shift_decider.param.yaml (100%) rename {control_launch/config => autoware_launch/config/control}/trajectory_follower/lateral/mpc.param.yaml (100%) create mode 100644 autoware_launch/config/control/trajectory_follower/lateral/pure_pursuit.param.yaml rename {control_launch/config => autoware_launch/config/control}/trajectory_follower/longitudinal/pid.param.yaml (100%) rename {control_launch/config => autoware_launch/config/control}/trajectory_follower/trajectory_follower_node.param.yaml (100%) rename {control_launch/config => autoware_launch/config/control}/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml (84%) create mode 100644 autoware_launch/launch/components/tier4_control_component.launch.xml delete mode 100644 control_launch/CMakeLists.txt delete mode 100644 control_launch/README.md delete mode 100644 control_launch/config/trajectory_follower/lateral/pure_pursuit.param.yaml delete mode 100644 control_launch/control_launch.drawio.svg delete mode 100644 control_launch/launch/control.launch.py delete mode 100644 control_launch/launch/control.launch.xml delete mode 100644 control_launch/package.xml diff --git a/control_launch/config/common/nearest_search.param.yaml b/autoware_launch/config/control/common/nearest_search.param.yaml similarity index 100% rename from control_launch/config/common/nearest_search.param.yaml rename to autoware_launch/config/control/common/nearest_search.param.yaml diff --git a/autoware_launch/config/control/external_cmd_selector/external_cmd_selector.param.yaml b/autoware_launch/config/control/external_cmd_selector/external_cmd_selector.param.yaml new file mode 100644 index 0000000000..6556656cc8 --- /dev/null +++ b/autoware_launch/config/control/external_cmd_selector/external_cmd_selector.param.yaml @@ -0,0 +1,4 @@ +/**: + ros__parameters: + update_rate: 10.0 + initial_selector_mode: "local" # ["local", "remote"] diff --git a/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml new file mode 100644 index 0000000000..092a6765aa --- /dev/null +++ b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml @@ -0,0 +1,15 @@ +/**: + ros__parameters: + # Node + update_rate: 10.0 + visualize_lanelet: false + + # Core + footprint_margin_scale: 1.0 + resample_interval: 0.3 + max_deceleration: 2.8 + delay_time: 1.3 + max_lateral_deviation: 2.0 + max_longitudinal_deviation: 2.0 + max_yaw_deviation_deg: 60.0 + delta_yaw_threshold_for_closest_point: 1.570 #M_PI/2.0, delta yaw thres for closest point diff --git a/autoware_launch/config/control/obstacle_collision_checker/obstacle_collision_checker.param.yaml b/autoware_launch/config/control/obstacle_collision_checker/obstacle_collision_checker.param.yaml new file mode 100644 index 0000000000..e3c78c90e2 --- /dev/null +++ b/autoware_launch/config/control/obstacle_collision_checker/obstacle_collision_checker.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + # Node + update_rate: 10.0 + + # Core + delay_time: 0.03 # delay time of vehicle [s] + footprint_margin: 0.0 # margin for footprint [m] + max_deceleration: 1.5 # max deceleration [m/ss] + resample_interval: 0.3 # interval distance to resample point cloud [m] + search_radius: 5.0 # search distance from trajectory to point cloud [m] diff --git a/control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml b/autoware_launch/config/control/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml similarity index 100% rename from control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml rename to autoware_launch/config/control/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml diff --git a/control_launch/config/shift_decider/shift_decider.param.yaml b/autoware_launch/config/control/shift_decider/shift_decider.param.yaml similarity index 100% rename from control_launch/config/shift_decider/shift_decider.param.yaml rename to autoware_launch/config/control/shift_decider/shift_decider.param.yaml diff --git a/control_launch/config/trajectory_follower/lateral/mpc.param.yaml b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml similarity index 100% rename from control_launch/config/trajectory_follower/lateral/mpc.param.yaml rename to autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml diff --git a/autoware_launch/config/control/trajectory_follower/lateral/pure_pursuit.param.yaml b/autoware_launch/config/control/trajectory_follower/lateral/pure_pursuit.param.yaml new file mode 100644 index 0000000000..0b8b464e9f --- /dev/null +++ b/autoware_launch/config/control/trajectory_follower/lateral/pure_pursuit.param.yaml @@ -0,0 +1,16 @@ +/**: + ros__parameters: + ld_velocity_ratio: 2.4 + ld_lateral_error_ratio: 3.6 + ld_curvature_ratio: 120.0 + long_ld_lateral_error_threshold: 0.5 + min_lookahead_distance: 4.35 + max_lookahead_distance: 15.0 + converged_steer_rad: 0.1 + reverse_min_lookahead_distance: 7.0 + prediction_ds: 0.3 + prediction_distance_length: 21.0 + resampling_ds: 0.1 + curvature_calculation_distance: 4.0 + enable_path_smoothing: false + path_filter_moving_ave_num: 25 diff --git a/control_launch/config/trajectory_follower/longitudinal/pid.param.yaml b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml similarity index 100% rename from control_launch/config/trajectory_follower/longitudinal/pid.param.yaml rename to autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml diff --git a/control_launch/config/trajectory_follower/trajectory_follower_node.param.yaml b/autoware_launch/config/control/trajectory_follower/trajectory_follower_node.param.yaml similarity index 100% rename from control_launch/config/trajectory_follower/trajectory_follower_node.param.yaml rename to autoware_launch/config/control/trajectory_follower/trajectory_follower_node.param.yaml diff --git a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml b/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml similarity index 84% rename from control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml rename to autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml index 351ad877e1..1a1d807858 100644 --- a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml +++ b/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml @@ -2,6 +2,9 @@ ros__parameters: update_rate: 10.0 system_emergency_heartbeat_timeout: 0.5 + use_emergency_handling: false + check_external_emergency_heartbeat: false + use_start_request: false external_emergency_stop_heartbeat_timeout: 0.0 stop_hold_acceleration: -1.5 emergency_acceleration: -2.4 diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index aaeaa13d39..f964f2da2b 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -35,8 +35,6 @@ - - @@ -120,13 +118,13 @@ - - + + + + - - - + diff --git a/autoware_launch/launch/components/tier4_control_component.launch.xml b/autoware_launch/launch/components/tier4_control_component.launch.xml new file mode 100644 index 0000000000..264deb0ffc --- /dev/null +++ b/autoware_launch/launch/components/tier4_control_component.launch.xml @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 77e13311cc..62fc034a6e 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -47,8 +47,6 @@ - -
    diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 7b17634425..eaa526cead 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -11,7 +11,6 @@ ament_cmake_auto ad_api_adaptors - control_launch global_parameter_loader planning_launch python3-bson @@ -19,6 +18,7 @@ rviz2 system_launch tier4_autoware_api_launch + tier4_control_launch tier4_localization_launch tier4_map_launch tier4_perception_launch diff --git a/control_launch/CMakeLists.txt b/control_launch/CMakeLists.txt deleted file mode 100644 index 206bb55e10..0000000000 --- a/control_launch/CMakeLists.txt +++ /dev/null @@ -1,23 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(control_launch) - -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() - -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 - launch -) diff --git a/control_launch/README.md b/control_launch/README.md deleted file mode 100644 index f18eedc3c9..0000000000 --- a/control_launch/README.md +++ /dev/null @@ -1,24 +0,0 @@ -# control_launch - -## Structure - -![control_launch](./control_launch.drawio.svg) - -## Package Dependencies - -Please see `` in `package.xml`. - -## Usage - -You can include as follows in `*.launch.xml` to use `control.launch.py`. - -```xml - - - - -``` - -## Notes - -For reducing processing load, we use the [Component](https://docs.ros.org/en/galactic/Concepts/About-Composition.html) feature in ROS2 (similar to Nodelet in ROS1 ) diff --git a/control_launch/config/trajectory_follower/lateral/pure_pursuit.param.yaml b/control_launch/config/trajectory_follower/lateral/pure_pursuit.param.yaml deleted file mode 100644 index acbb3a85a3..0000000000 --- a/control_launch/config/trajectory_follower/lateral/pure_pursuit.param.yaml +++ /dev/null @@ -1,9 +0,0 @@ -/**: - ros__parameters: - # -- 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/control_launch.drawio.svg b/control_launch/control_launch.drawio.svg deleted file mode 100644 index f51b6ba126..0000000000 --- a/control_launch/control_launch.drawio.svg +++ /dev/null @@ -1,421 +0,0 @@ - - - - - - - -
    -
    -
    - container -
    -
    -
    - - package: rclcpp_components - -
    -
    -
    -
    -
    - - container... - -
    -
    - - - - -
    -
    -
    - control.launch.py -
    -
    -
    - - package: control_launch - -
    -
    -
    -
    -
    - - control.launch.py... - -
    -
    - - - - - - - -
    -
    -
    - mpc_follower -
    -
    -
    -
    - - mpc_follower - -
    -
    - - - - - -
    -
    -
    - pure_pursuit -
    -
    -
    -
    - - pure_pursuit - -
    -
    - - - - -
    -
    -
    - $(var lateral_controller_mode) -
    -
    -
    -
    - - $(var lateral_controller_mode) - -
    -
    - - - - -
    -
    -
    - launch name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - launch name... - -
    -
    - - - - -
    -
    -
    - ex: -
    -
    -
    -
    - - ex: - -
    -
    - - - - -
    -
    -
    - node name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - node name... - -
    -
    - - - - -
    -
    -
    - latlon_muxer -
    -
    -
    - - package: latlon_muxer - -
    -
    -
    -
    -
    - - latlon_muxer... - -
    -
    - - - - -
    -
    -
    - mpc_follower -
    -
    -
    - - package: mpc_follower - -
    -
    -
    -
    -
    - - mpc_follower... - -
    -
    - - - - -
    -
    -
    - pure_pursuit -
    -
    -
    - - package: pure_pursuit - -
    -
    -
    -
    -
    - - pure_pursuit... - -
    -
    - - - - -
    -
    -
    - velocity_controller -
    -
    -
    - - package: velocity_controller - -
    -
    -
    -
    -
    - - velocity_controller... - -
    -
    - - - - -
    -
    -
    - lane_departure_checker_node -
    -
    -
    - - package: lane_departure_checker_node - -
    -
    -
    -
    -
    - - lane_departure_checker_node... - -
    -
    - - - - -
    -
    -
    - shift_decider -
    -
    -
    - - package: shift_decider - -
    -
    -
    -
    -
    - - shift_decider... - -
    -
    - - - - -
    -
    -
    - vehicle_cmd_gate -
    -
    -
    - - package: vehicle_cmd_gate - -
    -
    -
    -
    -
    - - vehicle_cmd_gate... - -
    -
    - - - - -
    -
    -
    - external_cmd_converter -
    -
    -
    - - package: external_cmd_converter - -
    -
    -
    -
    -
    - - external_cmd_converter... - -
    -
    - - - - -
    -
    -
    - external_cmd_selector -
    -
    -
    - - package: external_cmd_selector - -
    -
    -
    -
    -
    - - external_cmd_selector... - -
    -
    - - - - -
    -
    -
    - other name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - other name... - -
    -
    -
    - - - - - Viewer does not support full SVG 1.1 - - - -
    diff --git a/control_launch/launch/control.launch.py b/control_launch/launch/control.launch.py deleted file mode 100644 index 0dc4d1e836..0000000000 --- a/control_launch/launch/control.launch.py +++ /dev/null @@ -1,382 +0,0 @@ -# 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.actions import GroupAction -from launch.actions import IncludeLaunchDescription -from launch.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import PushRosNamespace -from launch_ros.descriptions import ComposableNode -from launch_ros.substitutions import FindPackageShare -import yaml - - -def launch_setup(context, *args, **kwargs): - nearest_search_param_path = LaunchConfiguration("nearest_search_param_path").perform(context) - with open(nearest_search_param_path, "r") as f: - nearest_search_param = yaml.safe_load(f)["/**"]["ros__parameters"] - lat_controller_param_path = LaunchConfiguration("lat_controller_param_path").perform(context) - with open(lat_controller_param_path, "r") as f: - lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] - lon_controller_param_path = LaunchConfiguration("lon_controller_param_path").perform(context) - with open(lon_controller_param_path, "r") as f: - lon_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"] - trajectory_follower_node_param_path = LaunchConfiguration( - "trajectory_follower_node_param_path" - ).perform(context) - with open(trajectory_follower_node_param_path, "r") as f: - trajectory_follower_node_param = yaml.safe_load(f)["/**"]["ros__parameters"] - vehicle_cmd_gate_param_path = LaunchConfiguration("vehicle_cmd_gate_param_path").perform( - context - ) - with open(vehicle_cmd_gate_param_path, "r") as f: - vehicle_cmd_gate_param = yaml.safe_load(f)["/**"]["ros__parameters"] - lane_departure_checker_param_path = LaunchConfiguration( - "lane_departure_checker_param_path" - ).perform(context) - with open(lane_departure_checker_param_path, "r") as f: - lane_departure_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - operation_mode_transition_manager_param_path = LaunchConfiguration( - "operation_mode_transition_manager_param_path" - ).perform(context) - with open(operation_mode_transition_manager_param_path, "r") as f: - operation_mode_transition_manager_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - shift_decider_param_path = LaunchConfiguration("shift_decider_param_path").perform(context) - with open(shift_decider_param_path, "r") as f: - shift_decider_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - controller_component = ComposableNode( - package="trajectory_follower_node", - plugin="autoware::motion::control::trajectory_follower_node::Controller", - name="controller_node_exe", - namespace="trajectory_follower", - remappings=[ - ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), - ("~/input/current_odometry", "/localization/kinematic_state"), - ("~/input/current_steering", "/vehicle/status/steering_status"), - ("~/input/current_accel", "/localization/acceleration"), - ("~/output/predicted_trajectory", "lateral/predicted_trajectory"), - ("~/output/lateral_diagnostic", "lateral/diagnostic"), - ("~/output/slope_angle", "longitudinal/slope_angle"), - ("~/output/longitudinal_diagnostic", "longitudinal/diagnostic"), - ("~/output/control_cmd", "control_cmd"), - ], - parameters=[ - { - "ctrl_period": 0.03, - "lateral_controller_mode": LaunchConfiguration("lateral_controller_mode"), - "longitudinal_controller_mode": LaunchConfiguration("longitudinal_controller_mode"), - }, - nearest_search_param, - trajectory_follower_node_param, - lon_controller_param, - lat_controller_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # lane departure checker - lane_departure_component = ComposableNode( - package="lane_departure_checker", - plugin="lane_departure_checker::LaneDepartureCheckerNode", - name="lane_departure_checker_node", - namespace="trajectory_follower", - remappings=[ - ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/lanelet_map_bin", "/map/vector_map"), - ("~/input/route", "/planning/mission_planning/route"), - ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), - ( - "~/input/predicted_trajectory", - "/control/trajectory_follower/lateral/predicted_trajectory", - ), - ], - parameters=[nearest_search_param, lane_departure_checker_param], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # shift decider - shift_decider_component = ComposableNode( - package="shift_decider", - plugin="ShiftDecider", - name="shift_decider", - remappings=[ - ("input/control_cmd", "/control/trajectory_follower/control_cmd"), - ("input/state", "/autoware/state"), - ("output/gear_cmd", "/control/shift_decider/gear_cmd"), - ], - parameters=[ - shift_decider_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # vehicle cmd gate - vehicle_cmd_gate_component = ComposableNode( - package="vehicle_cmd_gate", - plugin="vehicle_cmd_gate::VehicleCmdGate", - name="vehicle_cmd_gate", - remappings=[ - ("input/emergency_state", "/system/emergency/emergency_state"), - ("input/steering", "/vehicle/status/steering_status"), - ("input/operation_mode", "/system/operation_mode/state"), - ("input/auto/control_cmd", "/control/trajectory_follower/control_cmd"), - ("input/auto/turn_indicators_cmd", "/planning/turn_indicators_cmd"), - ("input/auto/hazard_lights_cmd", "/planning/hazard_lights_cmd"), - ("input/auto/gear_cmd", "/control/shift_decider/gear_cmd"), - ("input/external/control_cmd", "/external/selected/control_cmd"), - ("input/external/turn_indicators_cmd", "/external/selected/turn_indicators_cmd"), - ("input/external/hazard_lights_cmd", "/external/selected/hazard_lights_cmd"), - ("input/external/gear_cmd", "/external/selected/gear_cmd"), - ("input/external_emergency_stop_heartbeat", "/external/selected/heartbeat"), - ("input/gate_mode", "/control/gate_mode_cmd"), - ("input/emergency/control_cmd", "/system/emergency/control_cmd"), - ("input/emergency/hazard_lights_cmd", "/system/emergency/hazard_lights_cmd"), - ("input/emergency/gear_cmd", "/system/emergency/gear_cmd"), - ("input/mrm_state", "/system/fail_safe/mrm_state"), - ("output/vehicle_cmd_emergency", "/control/command/emergency_cmd"), - ("output/control_cmd", "/control/command/control_cmd"), - ("output/gear_cmd", "/control/command/gear_cmd"), - ("output/turn_indicators_cmd", "/control/command/turn_indicators_cmd"), - ("output/hazard_lights_cmd", "/control/command/hazard_lights_cmd"), - ("output/gate_mode", "/control/current_gate_mode"), - ("output/engage", "/api/autoware/get/engage"), - ("output/external_emergency", "/api/autoware/get/emergency"), - ("output/operation_mode", "/control/vehicle_cmd_gate/operation_mode"), - ("~/service/engage", "/api/autoware/set/engage"), - ("~/service/external_emergency", "/api/autoware/set/emergency"), - # TODO(Takagi, Isamu): deprecated - ("input/engage", "/autoware/engage"), - ("~/service/external_emergency_stop", "~/external_emergency_stop"), - ("~/service/clear_external_emergency_stop", "~/clear_external_emergency_stop"), - ], - parameters=[ - vehicle_cmd_gate_param, - { - "use_emergency_handling": LaunchConfiguration("use_emergency_handling"), - "check_external_emergency_heartbeat": LaunchConfiguration( - "check_external_emergency_heartbeat" - ), - "use_start_request": LaunchConfiguration("use_start_request"), - }, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # operation mode transition manager - operation_mode_transition_manager_component = ComposableNode( - package="operation_mode_transition_manager", - plugin="operation_mode_transition_manager::OperationModeTransitionManager", - name="operation_mode_transition_manager", - remappings=[ - # input - ("kinematics", "/localization/kinematic_state"), - ("steering", "/vehicle/status/steering_status"), - ("trajectory", "/planning/scenario_planning/trajectory"), - ("control_cmd", "/control/command/control_cmd"), - ("control_mode_report", "/vehicle/status/control_mode"), - ("gate_operation_mode", "/control/vehicle_cmd_gate/operation_mode"), - # output - ("is_autonomous_available", "/control/is_autonomous_available"), - ("control_mode_request", "/control/control_mode_request"), - ], - parameters=[ - nearest_search_param, - operation_mode_transition_manager_param, - ], - ) - - # external cmd selector - external_cmd_selector_loader = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - [FindPackageShare("external_cmd_selector"), "/launch/external_cmd_selector.launch.py"] - ), - launch_arguments=[ - ("use_intra_process", LaunchConfiguration("use_intra_process")), - ("target_container", "/control/control_container"), - # This is temporary uncomment. I will replace control_launch with tier4_control_launch soon. - # ("initial_selector_mode", LaunchConfiguration("initial_selector_mode")), - ( - "external_cmd_selector_param_path", - LaunchConfiguration("external_cmd_selector_param_path"), - ), - ], - ) - - # external cmd converter - external_cmd_converter_loader = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - [FindPackageShare("external_cmd_converter"), "/launch/external_cmd_converter.launch.py"] - ), - launch_arguments=[ - ("use_intra_process", LaunchConfiguration("use_intra_process")), - ("target_container", "/control/control_container"), - ], - ) - - container = ComposableNodeContainer( - name="control_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[ - controller_component, - lane_departure_component, - shift_decider_component, - vehicle_cmd_gate_component, - operation_mode_transition_manager_component, - ], - ) - - group = GroupAction( - [ - PushRosNamespace("control"), - container, - external_cmd_selector_loader, - external_cmd_converter_loader, - ] - ) - - return [group] - - -def generate_launch_description(): - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None, description=None): - launch_arguments.append( - DeclareLaunchArgument(name, default_value=default_value, description=description) - ) - - # lateral controller mode - add_launch_arg( - "lateral_controller_mode", - "mpc", - "lateral controller mode: `mpc` or `pure_pursuit`", - ) - - # longitudinal controller mode - add_launch_arg( - "longitudinal_controller_mode", - "pid", - "longitudinal controller mode: `pid`", - ) - - # parameter file path - add_launch_arg( - "nearest_search_param_path", - [ - FindPackageShare("control_launch"), - "/config/common/nearest_search.param.yaml", - ], - "path to the parameter file of nearest search", - ) - add_launch_arg( - "lat_controller_param_path", - [ - FindPackageShare("control_launch"), - "/config/trajectory_follower/lateral/mpc.param.yaml", - ], - "path to the parameter file of lateral controller. default is `mpc_follower`", - ) - add_launch_arg( - "lon_controller_param_path", - [ - FindPackageShare("control_launch"), - "/config/trajectory_follower/longitudinal/pid.param.yaml", - ], - "path to the parameter file of longitudinal controller", - ) - add_launch_arg( - "trajectory_follower_node_param_path", - [ - FindPackageShare("control_launch"), - "/config/trajectory_follower/trajectory_follower_node.param.yaml", - ], - "path to the parameter file of longitudinal controller", - ) - add_launch_arg( - "vehicle_cmd_gate_param_path", - [ - FindPackageShare("control_launch"), - "/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml", - ], - "path to the parameter file of vehicle_cmd_gate", - ) - add_launch_arg( - "lane_departure_checker_param_path", - [FindPackageShare("lane_departure_checker"), "/config/lane_departure_checker.param.yaml"], - ) - add_launch_arg( - "operation_mode_transition_manager_param_path", - [ - FindPackageShare("control_launch"), - "/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml", - ], - "path to the parameter file of vehicle_cmd_gate", - ) - add_launch_arg( - "shift_decider_param_path", - [ - FindPackageShare("control_launch"), - "/config/shift_decider/shift_decider.param.yaml", - ], - "path to the parameter file of shift_decider", - ) - - # vehicle cmd gate - add_launch_arg("use_emergency_handling", "false", "use emergency handling") - add_launch_arg("check_external_emergency_heartbeat", "true", "use external emergency stop") - add_launch_arg("use_start_request", "false", "use start request service") - - # external cmd selector - add_launch_arg("initial_selector_mode", "remote", "local or remote") - add_launch_arg( - "external_cmd_selector_param_path", - [ - FindPackageShare("external_cmd_selector"), - "/config/external_cmd_selector.param.yaml", - ], - ) - - # component - add_launch_arg("use_intra_process", "false", "use ROS2 component container communication") - add_launch_arg("use_multithread", "false", "use multithread") - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - return launch.LaunchDescription( - launch_arguments - + [ - set_container_executable, - set_container_mt_executable, - ] - + [OpaqueFunction(function=launch_setup)] - ) diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml deleted file mode 100644 index f5d6696cc4..0000000000 --- a/control_launch/launch/control.launch.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/control_launch/package.xml b/control_launch/package.xml deleted file mode 100644 index ebf76a49f8..0000000000 --- a/control_launch/package.xml +++ /dev/null @@ -1,26 +0,0 @@ - - - - control_launch - 0.1.0 - The control_launch package - - Takamasa Horibe - - Apache License 2.0 - - ament_cmake_auto - - external_cmd_converter - lane_departure_checker - shift_decider - trajectory_follower_node - vehicle_cmd_gate - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - From 8f447e1598174e3091dc0c2d21daab75a74370d2 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 20 Jan 2023 12:38:25 +0900 Subject: [PATCH 757/851] refactor(autoware_launch): remove planning_launch, and use tier4_planning_launch instead (#712) * refactor(autoware_launch): remove planning_launch, and use tier4_planning_launch instead Signed-off-by: Takayuki Murooka * add tier4_planning_component.launch.xml Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../common/common.param.yaml | 0 .../Analytical.param.yaml | 0 .../JerkFiltered.param.yaml | 0 .../motion_velocity_smoother/L2.param.yaml | 0 .../motion_velocity_smoother/Linf.param.yaml | 0 .../motion_velocity_smoother.param.yaml | 2 +- .../common/nearest_search.param.yaml | 0 .../avoidance/avoidance.param.yaml | 0 .../behavior_path_planner.param.yaml | 9 +- .../behavior_path_planner_tree.xml | 94 ++++ ...ior_path_planner_tree_lane_change_only.xml | 86 +++ .../behavior_path_planner_tree_pull_out.xml | 100 ++++ .../drivable_area_expansion.param.yaml | 0 .../lane_change/lane_change.param.yaml | 6 +- .../lane_following/lane_following.param.yaml | 0 .../pull_out/pull_out.param.yaml | 4 +- .../pull_over/pull_over.param.yaml | 8 +- .../side_shift/side_shift.param.yaml | 1 - .../behavior_velocity_planner.param.yaml | 2 + .../blind_spot.param.yaml | 0 .../crosswalk.param.yaml | 1 + .../detection_area.param.yaml | 1 - .../intersection.param.yaml | 2 +- .../no_stopping_area.param.yaml | 0 .../occlusion_spot.param.yaml | 10 +- .../run_out.param.yaml | 0 .../speed_bump.param.yaml | 13 + .../stop_line.param.yaml | 3 +- .../traffic_light.param.yaml | 0 .../virtual_traffic_light.param.yaml | 1 - .../lane_change_planner.param.yaml | 0 .../rtc_auto_mode_manager.param.yaml | 0 .../obstacle_avoidance_planner.param.yaml | 0 .../obstacle_cruise_planner.param.yaml | 0 .../adaptive_cruise_control.param.yaml | 0 .../obstacle_stop_planner.param.yaml | 3 + .../obstacle_velocity_limiter.param.yaml | 0 .../surround_obstacle_checker.param.yaml | 2 +- .../freespace_planner.param.yaml | 6 +- autoware_launch/launch/autoware.launch.xml | 12 +- .../tier4_planning_component.launch.xml | 123 +++++ autoware_launch/package.xml | 2 +- planning_launch/CMakeLists.txt | 23 - planning_launch/README.md | 16 - .../planning_error_monitor.param.yaml | 7 - .../mission_planning.launch.xml | 9 - planning_launch/launch/planning.launch.xml | 34 -- .../planning_error_monitor.launch.xml | 10 - .../scenario_planning/lane_driving.launch.xml | 36 -- .../behavior_planning.launch.py | 498 ------------------ .../behavior_planning.launch.xml | 26 - .../behavior_planning/compare_map.launch.py | 89 ---- .../vector_map_inside_area_filter.launch.py | 88 ---- .../motion_planning/motion_planning.launch.py | 338 ------------ .../motion_planning.launch.xml | 40 -- .../scenario_planning/parking.launch.py | 137 ----- .../scenario_planning/parking.launch.xml | 24 - .../scenario_planning.launch.xml | 57 -- planning_launch/package.xml | 31 -- planning_launch/planning_launch.drawio.svg | 318 ----------- 60 files changed, 461 insertions(+), 1811 deletions(-) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/common/common.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/common/motion_velocity_smoother/L2.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml (97%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/common/nearest_search.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml (80%) create mode 100644 autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree.xml create mode 100644 autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree_lane_change_only.xml create mode 100644 autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree_pull_out.xml rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml (85%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml (91%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml (91%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml (85%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml (80%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml (96%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml (83%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml (95%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml (88%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml (100%) create mode 100644 autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/speed_bump.param.yaml rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml (52%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml (85%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml (91%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml (100%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml (77%) rename {planning_launch/config => autoware_launch/config/planning}/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml (85%) create mode 100644 autoware_launch/launch/components/tier4_planning_component.launch.xml delete mode 100644 planning_launch/CMakeLists.txt delete mode 100644 planning_launch/README.md delete mode 100644 planning_launch/config/planning_diagnostics/planning_error_monitor.param.yaml delete mode 100644 planning_launch/launch/mission_planning/mission_planning.launch.xml delete mode 100644 planning_launch/launch/planning.launch.xml delete mode 100644 planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml delete mode 100644 planning_launch/launch/scenario_planning/lane_driving.launch.xml delete mode 100644 planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py delete mode 100644 planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml delete mode 100644 planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py delete mode 100644 planning_launch/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py delete mode 100644 planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py delete mode 100644 planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml delete mode 100644 planning_launch/launch/scenario_planning/parking.launch.py delete mode 100644 planning_launch/launch/scenario_planning/parking.launch.xml delete mode 100644 planning_launch/launch/scenario_planning/scenario_planning.launch.xml delete mode 100644 planning_launch/package.xml delete mode 100644 planning_launch/planning_launch.drawio.svg diff --git a/planning_launch/config/scenario_planning/common/common.param.yaml b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/common/common.param.yaml rename to autoware_launch/config/planning/scenario_planning/common/common.param.yaml diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml rename to autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml rename to autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/L2.param.yaml b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/L2.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/common/motion_velocity_smoother/L2.param.yaml rename to autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/L2.param.yaml diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml rename to autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml similarity index 97% rename from planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml rename to autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index 7f90e07b40..64b2d95c6f 100644 --- a/planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -9,7 +9,7 @@ # curve parameters max_lateral_accel: 1.0 # max lateral acceleration limit [m/ss] - min_curve_velocity: 2.74 # min velocity at lateral acceleration limit [m/ss] + min_curve_velocity: 0.5 # min velocity at lateral acceleration limit and steering angle rate 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 min_decel_for_lateral_acc_lim_filter: -2.5 # deceleration limit applied in the lateral acceleration filter to avoid sudden braking [m/ss] diff --git a/planning_launch/config/scenario_planning/common/nearest_search.param.yaml b/autoware_launch/config/planning/scenario_planning/common/nearest_search.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/common/nearest_search.param.yaml rename to autoware_launch/config/planning/scenario_planning/common/nearest_search.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml similarity index 80% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index e34fa49cba..055cec3acb 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + planning_hz: 10.0 backward_path_length: 5.0 forward_path_length: 300.0 backward_length_buffer_for_end_of_pull_over: 5.0 @@ -14,6 +15,7 @@ turn_signal_minimum_search_distance: 10.0 turn_signal_search_time: 3.0 turn_signal_shift_length_threshold: 0.3 + turn_signal_on_swerving: true path_interval: 2.0 @@ -21,11 +23,12 @@ lateral_distance_max_threshold: 2.0 longitudinal_distance_min_threshold: 3.0 + expected_front_deceleration: -1.0 expected_rear_deceleration: -1.0 - expected_front_deceleration_for_abort: -1.0 - expected_rear_deceleration_for_abort: -2.0 + expected_front_deceleration_for_abort: -2.0 + expected_rear_deceleration_for_abort: -2.5 rear_vehicle_reaction_time: 2.0 - rear_vehicle_safety_time_margin: 2.0 + rear_vehicle_safety_time_margin: 1.0 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree.xml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree.xml new file mode 100644 index 0000000000..748b70b33f --- /dev/null +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree.xml @@ -0,0 +1,94 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + desc + + + desc + + + + + + desc + + + desc + + + + desc + + + desc + + + + + + + + desc + + + + + desc + + + desc + + + + + + + + diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree_lane_change_only.xml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree_lane_change_only.xml new file mode 100644 index 0000000000..5c4d2b589d --- /dev/null +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree_lane_change_only.xml @@ -0,0 +1,86 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + desc + + + desc + + + + + + desc + + + desc + + + + desc + + + desc + + + + + + + + desc + + + + + desc + + + desc + + + + + + + + diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree_pull_out.xml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree_pull_out.xml new file mode 100644 index 0000000000..e5876e9287 --- /dev/null +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree_pull_out.xml @@ -0,0 +1,100 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + desc + + + desc + + + + + + + + + desc + + + desc + + + + + desc + + + desc + + + + + + + + + + desc + + + + + + desc + + + desc + + + + + + + + + diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml similarity index 85% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml index 891e54a544..41de868418 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -5,9 +5,9 @@ lane_changing_safety_check_duration: 8.0 # [s] minimum_lane_change_prepare_distance: 2.0 # [m] - minimum_lane_change_length: 16.5 - backward_length_buffer_for_end_of_lane: 2.0 - lane_change_finish_judge_buffer: 3.0 # [m] + minimum_lane_change_length: 16.5 # [m] + backward_length_buffer_for_end_of_lane: 3.0 # [m] + lane_change_finish_judge_buffer: 2.0 # [m] lane_changing_lateral_jerk: 0.5 # [m/s3] lane_changing_lateral_acc: 0.5 # [m/s2] diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml similarity index 91% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml index 68000747b7..9fcbc2a173 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml @@ -5,18 +5,18 @@ th_stopped_velocity: 0.01 th_stopped_time: 1.0 collision_check_margin: 1.0 - collision_check_distance_from_end: 1.0 + pull_out_finish_judge_buffer: 1.0 # shift pull out enable_shift_pull_out: true shift_pull_out_velocity: 2.0 pull_out_sampling_num: 4 + before_pull_out_straight_distance: 0.0 minimum_shift_pull_out_distance: 20.0 maximum_lateral_jerk: 2.0 minimum_lateral_jerk: 0.5 deceleration_interval: 15.0 # geometric pull out enable_geometric_pull_out: true - divide_pull_out_path: false geometric_pull_out_velocity: 1.0 arc_path_interval: 1.0 lane_departure_margin: 0.2 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml similarity index 91% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index f09439edf7..44d859a477 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: pull_over: - request_length: 100.0 + request_length: 200.0 th_arrived_distance: 1.0 th_stopped_velocity: 0.01 th_stopped_time: 2.0 # It must be greater than the state_machine's. @@ -17,9 +17,6 @@ backward_goal_search_length: 20.0 goal_search_interval: 2.0 longitudinal_margin: 3.0 - max_lateral_offset: 0.5 - lateral_offset_interval: 0.25 - ignore_distance_from_lane_start: 15.0 # occupancy grid map use_occupancy_grid: true use_occupancy_grid_for_longitudinal_margin: false @@ -35,7 +32,8 @@ maximum_lateral_jerk: 2.0 minimum_lateral_jerk: 0.5 deceleration_interval: 15.0 - after_pull_over_straight_distance: 1.0 + after_pull_over_straight_distance: 5.0 + before_pull_over_straight_distance: 5.0 # parallel parking path enable_arc_forward_parking: true enable_arc_backward_parking: true diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml similarity index 85% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml index 815301d55a..79044041b4 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml @@ -6,4 +6,3 @@ shifting_lateral_jerk: 0.2 min_shifting_distance: 5.0 min_shifting_speed: 5.56 - shift_request_time_limit: 1.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml similarity index 80% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml index 5ac74c2015..7aab0af21f 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml @@ -10,9 +10,11 @@ launch_occlusion_spot: true launch_no_stopping_area: true launch_run_out: false + launch_speed_bump: false forward_path_length: 1000.0 backward_path_length: 5.0 max_accel: -2.8 max_jerk: -5.0 system_delay: 0.5 delay_response_time: 0.5 + is_publish_debug_path: false # publish all debug path with lane id in each module diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml similarity index 96% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml index 2cc5260e4e..2bbc5d31fc 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml @@ -26,6 +26,7 @@ stop_object_velocity_threshold: 0.28 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.28 m/s = 1.0 kmph) min_object_velocity: 1.39 # [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV. 1.39 m/s = 5.0 kmph) max_yield_timeout: 3.0 # [s] if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first. + ego_yield_query_stop_duration: 0.1 # [s] the amount of time which ego should be stopping to query whether it yields or not # param for input data tl_state_timeout: 3.0 # [s] timeout threshold for traffic light signal diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml similarity index 83% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml index 63ca5fc7d9..9174045bf0 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml @@ -6,4 +6,3 @@ dead_line_margin: 5.0 use_pass_judge_line: false state_clear_time: 2.0 - hold_stop_margin_distance: 0.0 diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml similarity index 95% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index f78e8b16aa..220c087d18 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -19,7 +19,7 @@ collision_start_margin_time: 5.0 # [s] collision_end_margin_time: 2.0 # [s] use_stuck_stopline: false # stopline generate before the intersection lanelet when is_stuck - assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of frontcar when frontcar as well as ego are turning + assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of front car when front car as well as ego are turning enable_front_car_decel_prediction: false # By default this feature is disabled merge_from_private_road: diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml similarity index 88% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml index 0b93ea5308..957f7988a6 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml @@ -4,7 +4,7 @@ detection_method: "occupancy_grid" # [-] candidate is "occupancy_grid" or "predicted_object" pass_judge: "smooth_velocity" # [-] candidate is "smooth_velocity" or "current_velocity" use_object_info: true # [-] whether to reflect object info to occupancy grid map or not - use_moving_object_ray_cast: true # [-] whether to reflect moving object ray shadow grid map + use_moving_object_ray_cast: true # [-] whether to reflect moving object ray_cast to occupancy grid map or not use_partition_lanelet: true # [-] whether to use partition lanelet map data pedestrian_vel: 1.5 # [m/s] assume pedestrian is dashing from occlusion at this velocity pedestrian_radius: 0.3 # [m] assume pedestrian width(0.2m) + margin(0.1m) @@ -18,8 +18,8 @@ lateral_distance: 1.5 # [m] maximum lateral distance to consider hidden collision motion: safety_ratio: 0.8 # [-] jerk/acceleration ratio for safety - max_slow_down_jerk: -0.3 # [m/s^3] minimum jerk deceleration for safe brake. - max_slow_down_accel: -1.5 # [m/s^2] minimum accel deceleration for safe brake. + max_slow_down_jerk: -0.5 # [m/s^3] minimum jerk deceleration for safe brake. + max_slow_down_accel: -1.8 # [m/s^2] minimum accel deceleration for safe brake. non_effective_jerk: -0.3 # [m/s^3] weak jerk for velocity planning. non_effective_acceleration: -1.0 # [m/s^2] weak deceleration for velocity planning. min_allowed_velocity: 1.0 # [m/s] minimum velocity allowed @@ -28,7 +28,7 @@ min_occlusion_spot_size: 1.0 # [m] occupancy grid must contain an UNKNOWN area of at least size NxN to be considered a hidden obstacle. slice_length: 10.0 # [m] size of slices in both length and distance relative to the ego path. min_longitudinal_offset: 1.0 # [m] detection area safety buffer from front bumper. - max_lateral_distance: 5.0 # [m] buffer around the ego path used to build the detection area. + max_lateral_distance: 6.0 # [m] buffer around the ego path used to build the detection area. grid: free_space_max: 43 # [-] maximum value of a free space cell in the occupancy grid - occupied_min: 57 # [-] minimum value of an occupied cell in the occupancy grid + occupied_min: 58 # [-] minimum value of an occupied cell in the occupancy grid diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/speed_bump.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/speed_bump.param.yaml new file mode 100644 index 0000000000..ef61bdb743 --- /dev/null +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/speed_bump.param.yaml @@ -0,0 +1,13 @@ +/**: + ros__parameters: + speed_bump: + slow_start_margin: 1.0 + slow_end_margin: 1.0 + print_debug_info: false + + # limits for speed bump height and slow down speed to create a linear equation + speed_calculation: + min_height: 0.05 # [m] + max_height: 0.30 # [m] + min_speed: 1.39 # [m/s] = [5 kph] + max_speed: 2.78 # [m/s] = [10 kph] diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml similarity index 52% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml index 0118452b72..a2b5ac5d5f 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml @@ -2,6 +2,5 @@ ros__parameters: stop_line: stop_margin: 0.0 + stop_check_dist: 2.0 stop_duration_sec: 1.0 - hold_stop_margin_distance: 2.0 - use_initialization_stop_line_state: true diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml similarity index 85% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml index 8879408d40..267dde50c7 100644 --- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml @@ -4,6 +4,5 @@ max_delay_sec: 3.0 near_line_distance: 1.0 dead_line_margin: 1.0 - hold_stop_margin_distance: 0.0 max_yaw_deviation_deg: 90.0 check_timeout_after_stop_line: true diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/autoware_launch/config/planning/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.param.yaml rename to autoware_launch/config/planning/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/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml similarity index 91% rename from planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml index 55a21d6cd7..8954a46ab1 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml @@ -4,6 +4,9 @@ lowpass_gain: 0.9 # gain parameter for low pass filter [-] max_velocity: 20.0 # max velocity [m/s] enable_slow_down: False # whether to use slow down planner [-] + voxel_grid_x: 0.05 # voxel grid x parameter for filtering pointcloud [m] + voxel_grid_y: 0.05 # voxel grid y parameter for filtering pointcloud [m] + voxel_grid_z: 100000.0 # voxel grid z parameter for filtering pointcloud [m] stop_planner: # params for stop position diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml similarity index 77% rename from planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml index 982fb7e1d7..6aa4e71774 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml @@ -12,4 +12,4 @@ stop_state_ego_speed: 0.1 #[m/s] # debug - publish_debug_footprints: false # publish vehicle footprint & footprints with surround_check_distance and surround_check_recover_distance offsets + publish_debug_footprints: true # publish vehicle footprint & footprints with surround_check_distance and surround_check_recover_distance offsets diff --git a/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml similarity index 85% rename from planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml rename to autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml index d2226091b5..d6152c4f56 100644 --- a/planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: # -- Node Configurations -- - planning_algorithm: "astar" # options: astar, rrtstar + planning_algorithm: "astar" waypoints_velocity: 5.0 update_rate: 10.0 th_arrived_distance_m: 1.0 @@ -15,6 +15,10 @@ # -- Configurations common to the all planners -- # base configs time_limit: 30000.0 + # robot configs # TODO replace by vehicle_info + robot_length: 4.5 + robot_width: 1.75 + robot_base2back: 1.0 minimum_turning_radius: 9.0 maximum_turning_radius: 9.0 turning_radius_size: 1 diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index f964f2da2b..c848c487a6 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -109,10 +109,18 @@ - + + - + + + + + diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml new file mode 100644 index 0000000000..b0ee0489ba --- /dev/null +++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml @@ -0,0 +1,123 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index eaa526cead..4cc04cc4f4 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -12,7 +12,6 @@ ad_api_adaptors global_parameter_loader - planning_launch python3-bson python3-tornado rviz2 @@ -22,6 +21,7 @@ tier4_localization_launch tier4_map_launch tier4_perception_launch + tier4_planning_launch tier4_sensing_launch tier4_simulator_launch tier4_vehicle_launch diff --git a/planning_launch/CMakeLists.txt b/planning_launch/CMakeLists.txt deleted file mode 100644 index de7ef164be..0000000000 --- a/planning_launch/CMakeLists.txt +++ /dev/null @@ -1,23 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(planning_launch) - -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() - -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 - config -) diff --git a/planning_launch/README.md b/planning_launch/README.md deleted file mode 100644 index 84bf70d26b..0000000000 --- a/planning_launch/README.md +++ /dev/null @@ -1,16 +0,0 @@ -# planning_launch - -## Structure - -![planning_launch](./planning_launch.drawio.svg) - -## Package Dependencies - -Please see `` in `package.xml`. - -## Usage - -```xml - - -``` diff --git a/planning_launch/config/planning_diagnostics/planning_error_monitor.param.yaml b/planning_launch/config/planning_diagnostics/planning_error_monitor.param.yaml deleted file mode 100644 index d52f24553b..0000000000 --- a/planning_launch/config/planning_diagnostics/planning_error_monitor.param.yaml +++ /dev/null @@ -1,7 +0,0 @@ -/**: - ros__parameters: - # trajectory check - error_interval: 100.0 # error interval distance threshold [m] - error_curvature: 2.0 # error curvature threshold [rad/m] - error_sharp_angle: 0.785398 # error sharp angle threshold [rad] - ignore_too_close_points: 0.01 # ignore too close distance threshold [m] diff --git a/planning_launch/launch/mission_planning/mission_planning.launch.xml b/planning_launch/launch/mission_planning/mission_planning.launch.xml deleted file mode 100644 index c1ace97b97..0000000000 --- a/planning_launch/launch/mission_planning/mission_planning.launch.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/planning_launch/launch/planning.launch.xml b/planning_launch/launch/planning.launch.xml deleted file mode 100644 index 8116564f87..0000000000 --- a/planning_launch/launch/planning.launch.xml +++ /dev/null @@ -1,34 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml b/planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml deleted file mode 100644 index e3960f8ec0..0000000000 --- a/planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - - diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch.xml b/planning_launch/launch/scenario_planning/lane_driving.launch.xml deleted file mode 100644 index a762fefa93..0000000000 --- a/planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ /dev/null @@ -1,36 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py deleted file mode 100644 index 0f00aeb60f..0000000000 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ /dev/null @@ -1,498 +0,0 @@ -# Copyright 2021 Tier IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import os - -from ament_index_python.packages import get_package_share_directory -import launch -from launch.actions import DeclareLaunchArgument -from launch.actions import IncludeLaunchDescription -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration -from launch.substitutions import PythonExpression -from launch_ros.actions import ComposableNodeContainer -from launch_ros.descriptions import ComposableNode -from launch_ros.substitutions import FindPackageShare -import yaml - - -def generate_launch_description(): - nearest_search_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "common", - "nearest_search.param.yaml", - ) - with open(nearest_search_param_path, "r") as f: - nearest_search_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - # behavior path planner - side_shift_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_path_planner", - "side_shift", - "side_shift.param.yaml", - ) - with open(side_shift_param_path, "r") as f: - side_shift_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - avoidance_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_path_planner", - "avoidance", - "avoidance.param.yaml", - ) - with open(avoidance_param_path, "r") as f: - avoidance_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - lane_change_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_path_planner", - "lane_change", - "lane_change.param.yaml", - ) - with open(lane_change_param_path, "r") as f: - lane_change_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - lane_following_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_path_planner", - "lane_following", - "lane_following.param.yaml", - ) - with open(lane_following_param_path, "r") as f: - lane_following_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - pull_over_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_path_planner", - "pull_over", - "pull_over.param.yaml", - ) - with open(pull_over_param_path, "r") as f: - pull_over_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - pull_out_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_path_planner", - "pull_out", - "pull_out.param.yaml", - ) - with open(pull_out_param_path, "r") as f: - pull_out_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - drivable_area_expansion_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_path_planner", - "drivable_area_expansion.param.yaml", - ) - with open(drivable_area_expansion_param_path, "r") as f: - drivable_area_expansion_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - behavior_path_planner_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_path_planner", - "behavior_path_planner.param.yaml", - ) - with open(behavior_path_planner_param_path, "r") as f: - behavior_path_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - behavior_path_planner_component = ComposableNode( - package="behavior_path_planner", - plugin="behavior_path_planner::BehaviorPathPlannerNode", - name="behavior_path_planner", - namespace="", - remappings=[ - ("~/input/route", LaunchConfiguration("input_route_topic_name")), - ("~/input/vector_map", LaunchConfiguration("map_topic_name")), - ("~/input/perception", "/perception/object_recognition/objects"), - ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/accel", "/localization/acceleration"), - ("~/input/scenario", "/planning/scenario_planning/scenario"), - ("~/output/path", "path_with_lane_id"), - ("~/output/turn_indicators_cmd", "/planning/turn_indicators_cmd"), - ("~/output/hazard_lights_cmd", "/planning/hazard_lights_cmd"), - ], - parameters=[ - nearest_search_param, - side_shift_param, - avoidance_param, - lane_change_param, - lane_following_param, - pull_over_param, - pull_out_param, - drivable_area_expansion_param, - behavior_path_planner_param, - { - "bt_tree_config_path": [ - FindPackageShare("behavior_path_planner"), - "/config/behavior_path_planner_tree.xml", - ], - "planning_hz": 10.0, - }, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # smoother param - common_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "common", - "common.param.yaml", - ) - with open(common_param_path, "r") as f: - common_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - motion_velocity_smoother_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "common", - "motion_velocity_smoother", - "motion_velocity_smoother.param.yaml", - ) - with open(motion_velocity_smoother_param_path, "r") as f: - motion_velocity_smoother_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - smoother_type_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "common", - "motion_velocity_smoother", - "Analytical.param.yaml", - ) - with open(smoother_type_param_path, "r") as f: - smoother_type_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - # behavior velocity planner - blind_spot_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_velocity_planner", - "blind_spot.param.yaml", - ) - with open(blind_spot_param_path, "r") as f: - blind_spot_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - crosswalk_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_velocity_planner", - "crosswalk.param.yaml", - ) - with open(crosswalk_param_path, "r") as f: - crosswalk_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - detection_area_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_velocity_planner", - "detection_area.param.yaml", - ) - with open(detection_area_param_path, "r") as f: - detection_area_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - intersection_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_velocity_planner", - "intersection.param.yaml", - ) - with open(intersection_param_path, "r") as f: - intersection_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - stop_line_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_velocity_planner", - "stop_line.param.yaml", - ) - with open(stop_line_param_path, "r") as f: - stop_line_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - traffic_light_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_velocity_planner", - "traffic_light.param.yaml", - ) - with open(traffic_light_param_path, "r") as f: - traffic_light_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - virtual_traffic_light_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_velocity_planner", - "virtual_traffic_light.param.yaml", - ) - with open(virtual_traffic_light_param_path, "r") as f: - virtual_traffic_light_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - occlusion_spot_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_velocity_planner", - "occlusion_spot.param.yaml", - ) - with open(occlusion_spot_param_path, "r") as f: - occlusion_spot_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - no_stopping_area_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_velocity_planner", - "no_stopping_area.param.yaml", - ) - with open(no_stopping_area_param_path, "r") as f: - no_stopping_area_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - run_out_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_velocity_planner", - "run_out.param.yaml", - ) - with open(run_out_param_path, "r") as f: - run_out_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - behavior_velocity_planner_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "behavior_planning", - "behavior_velocity_planner", - "behavior_velocity_planner.param.yaml", - ) - with open(behavior_velocity_planner_param_path, "r") as f: - behavior_velocity_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - behavior_velocity_planner_component = ComposableNode( - package="behavior_velocity_planner", - plugin="behavior_velocity_planner::BehaviorVelocityPlannerNode", - name="behavior_velocity_planner", - namespace="", - remappings=[ - ("~/input/path_with_lane_id", "path_with_lane_id"), - ("~/input/vector_map", "/map/vector_map"), - ("~/input/vehicle_odometry", "/localization/kinematic_state"), - ("~/input/accel", "/localization/acceleration"), - ("~/input/dynamic_objects", "/perception/object_recognition/objects"), - ( - "~/input/no_ground_pointcloud", - "/perception/obstacle_segmentation/pointcloud", - ), - ( - "~/input/compare_map_filtered_pointcloud", - "compare_map_filtered/pointcloud", - ), - ( - "~/input/traffic_signals", - "/perception/traffic_light_recognition/traffic_signals", - ), - ( - "~/input/external_traffic_signals", - "/external/traffic_light_recognition/traffic_signals", - ), - ( - "~/input/external_velocity_limit_mps", - "/planning/scenario_planning/max_velocity_default", - ), - ("~/input/virtual_traffic_light_states", "/awapi/tmp/virtual_traffic_light_states"), - ( - "~/input/occupancy_grid", - "/perception/occupancy_grid_map/map", - ), - ("~/output/path", "path"), - ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), - ( - "~/output/infrastructure_commands", - "/planning/scenario_planning/status/infrastructure_commands", - ), - ("~/output/traffic_signal", "debug/traffic_signal"), - ], - parameters=[ - behavior_velocity_planner_param, - common_param, - nearest_search_param, - motion_velocity_smoother_param, - smoother_type_param, - blind_spot_param, - crosswalk_param, - detection_area_param, - intersection_param, - stop_line_param, - traffic_light_param, - virtual_traffic_light_param, - occlusion_spot_param, - no_stopping_area_param, - run_out_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - container = ComposableNodeContainer( - name="behavior_planning_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[ - behavior_path_planner_component, - behavior_velocity_planner_component, - ], - output="screen", - ) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - # This condition is true if run_out module is enabled and its detection method is Points - launch_run_out_with_points_method = PythonExpression( - [ - LaunchConfiguration( - "launch_run_out", default=behavior_velocity_planner_param["launch_run_out"] - ), - " and ", - "'", - run_out_param["run_out"]["detection_method"], - "' == 'Points'", - ] - ) - - # load compare map for run out module - load_compare_map = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - [ - FindPackageShare("planning_launch"), - "/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py", - ] - ), - launch_arguments={ - "use_pointcloud_container": LaunchConfiguration("use_pointcloud_container"), - "container_name": LaunchConfiguration("container_name"), - "use_multithread": "true", - }.items(), - # launch compare map only when run_out module is enabled and detection method is Points - condition=IfCondition(launch_run_out_with_points_method), - ) - - load_vector_map_inside_area_filter = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - [ - FindPackageShare("planning_launch"), - "/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py", - ] - ), - launch_arguments={ - "use_pointcloud_container": LaunchConfiguration("use_pointcloud_container"), - "container_name": LaunchConfiguration("container_name"), - "use_multithread": "true", - "polygon_type": "no_obstacle_segmentation_area_for_run_out", - }.items(), - # launch vector map filter only when run_out module is enabled and detection method is Points - condition=IfCondition(launch_run_out_with_points_method), - ) - - return launch.LaunchDescription( - [ - DeclareLaunchArgument( - "input_route_topic_name", default_value="/planning/mission_planning/route" - ), - DeclareLaunchArgument("map_topic_name", default_value="/map/vector_map"), - DeclareLaunchArgument("use_intra_process", default_value="false"), - DeclareLaunchArgument("use_multithread", default_value="false"), - set_container_executable, - set_container_mt_executable, - container, - load_compare_map, - load_vector_map_inside_area_filter, - ] - ) 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 deleted file mode 100644 index ddd7e8b894..0000000000 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py deleted file mode 100644 index 60b31f475e..0000000000 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py +++ /dev/null @@ -1,89 +0,0 @@ -# Copyright 2022 TIER IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode - - -def generate_launch_description(): - def add_launch_arg(name: str, default_value=None): - return DeclareLaunchArgument(name, default_value=default_value) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - composable_nodes = [ - ComposableNode( - package="compare_map_segmentation", - plugin="compare_map_segmentation::VoxelDistanceBasedCompareMapFilterComponent", - name="voxel_distance_based_compare_map_filter_node", - remappings=[ - ("input", "vector_map_inside_area_filtered/pointcloud"), - ("map", "/map/pointcloud_map"), - ("output", "compare_map_filtered/pointcloud"), - ], - parameters=[ - { - "distance_threshold": 0.7, - } - ], - extra_arguments=[ - {"use_intra_process_comms": False} # this node has QoS of transient local - ], - ), - ] - - compare_map_container = ComposableNodeContainer( - name="compare_map_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=composable_nodes, - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - - load_composable_nodes = LoadComposableNodes( - composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration("container_name"), - condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), - ) - - return LaunchDescription( - [ - add_launch_arg("use_multithread", "true"), - add_launch_arg("use_pointcloud_container", "true"), - add_launch_arg("container_name", "compare_map_container"), - set_container_executable, - set_container_mt_executable, - compare_map_container, - load_composable_nodes, - ] - ) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py deleted file mode 100644 index 3921dcfe7d..0000000000 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py +++ /dev/null @@ -1,88 +0,0 @@ -# Copyright 2022 TIER IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode - - -def generate_launch_description(): - def add_launch_arg(name: str, default_value=None): - return DeclareLaunchArgument(name, default_value=default_value) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - composable_nodes = [ - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::VectorMapInsideAreaFilterComponent", - name="vector_map_inside_area_filter_node", - remappings=[ - ("input", "/perception/obstacle_segmentation/pointcloud"), - ("input/vector_map", "/map/vector_map"), - ("output", "vector_map_inside_area_filtered/pointcloud"), - ], - parameters=[ - { - "polygon_type": LaunchConfiguration("polygon_type"), - } - ], - # this node has QoS of transient local - extra_arguments=[{"use_intra_process_comms": False}], - ), - ] - - vector_map_area_filter_container = ComposableNodeContainer( - name="vector_map_area_filter_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=composable_nodes, - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - - load_composable_nodes = LoadComposableNodes( - composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration("container_name"), - condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), - ) - - return LaunchDescription( - [ - add_launch_arg("use_multithread", "true"), - add_launch_arg("use_pointcloud_container", "true"), - add_launch_arg("container_name", "vector_map_area_filter_container"), - set_container_executable, - set_container_mt_executable, - vector_map_area_filter_container, - load_composable_nodes, - ] - ) diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py deleted file mode 100644 index 56a2468124..0000000000 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ /dev/null @@ -1,338 +0,0 @@ -# Copyright 2021 Tier IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import os - -from ament_index_python.packages import get_package_share_directory -import launch -from launch.actions import DeclareLaunchArgument -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import LaunchConfigurationEquals -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode -import yaml - - -def generate_launch_description(): - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None, description=None): - launch_arguments.append( - DeclareLaunchArgument(name, default_value=default_value, description=description) - ) - - add_launch_arg( - "cruise_planner_type", - "obstacle_stop_planner", - "cruise_planner: obstacle_stop_planner, obstacle_cruise_planner, none`", - ) - - # planning common param path - common_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "common", - "common.param.yaml", - ) - with open(common_param_path, "r") as f: - common_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - nearest_search_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "common", - "nearest_search.param.yaml", - ) - with open(nearest_search_param_path, "r") as f: - nearest_search_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - # obstacle avoidance planner - obstacle_avoidance_planner_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "motion_planning", - "obstacle_avoidance_planner", - "obstacle_avoidance_planner.param.yaml", - ) - with open(obstacle_avoidance_planner_param_path, "r") as f: - obstacle_avoidance_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] - obstacle_avoidance_planner_component = ComposableNode( - package="obstacle_avoidance_planner", - plugin="ObstacleAvoidancePlanner", - name="obstacle_avoidance_planner", - namespace="", - remappings=[ - ("~/input/objects", "/perception/object_recognition/objects"), - ("~/input/path", LaunchConfiguration("input_path_topic")), - ("~/output/path", "obstacle_avoidance_planner/trajectory"), - ], - parameters=[ - nearest_search_param, - obstacle_avoidance_planner_param, - {"is_showing_debug_info": False}, - {"is_stopping_if_outside_drivable_area": True}, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # obstacle velocity limiter - obstacle_velocity_limiter_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "motion_planning", - "obstacle_velocity_limiter", - "obstacle_velocity_limiter.param.yaml", - ) - with open(obstacle_velocity_limiter_param_path, "r") as f: - obstacle_velocity_limiter_param = yaml.safe_load(f)["/**"]["ros__parameters"] - obstacle_velocity_limiter_component = ComposableNode( - package="obstacle_velocity_limiter", - plugin="obstacle_velocity_limiter::ObstacleVelocityLimiterNode", - name="obstacle_velocity_limiter", - namespace="", - remappings=[ - ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), - ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/dynamic_obstacles", "/perception/object_recognition/objects"), - ("~/input/occupancy_grid", "/perception/occupancy_grid_map/map"), - ("~/input/obstacle_pointcloud", "/perception/obstacle_segmentation/pointcloud"), - ("~/input/map", "/map/vector_map"), - ("~/output/debug_markers", "debug_markers"), - ("~/output/trajectory", "obstacle_velocity_limiter/trajectory"), - ], - parameters=[ - obstacle_velocity_limiter_param, - {"obstacles.dynamic_source": "static_only"}, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # surround obstacle checker - surround_obstacle_checker_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "motion_planning", - "surround_obstacle_checker", - "surround_obstacle_checker.param.yaml", - ) - with open(surround_obstacle_checker_param_path, "r") as f: - surround_obstacle_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] - surround_obstacle_checker_component = ComposableNode( - package="surround_obstacle_checker", - plugin="surround_obstacle_checker::SurroundObstacleCheckerNode", - name="surround_obstacle_checker", - namespace="", - remappings=[ - ("~/output/no_start_reason", "/planning/scenario_planning/status/no_start_reason"), - ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), - ("~/output/max_velocity", "/planning/scenario_planning/max_velocity_candidates"), - ( - "~/output/velocity_limit_clear_command", - "/planning/scenario_planning/clear_velocity_limit", - ), - ( - "~/input/pointcloud", - "/perception/obstacle_segmentation/pointcloud", - ), - ("~/input/objects", "/perception/object_recognition/objects"), - ("~/input/odometry", "/localization/kinematic_state"), - ], - parameters=[ - nearest_search_param, - surround_obstacle_checker_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # obstacle cruise planner - obstacle_cruise_planner_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "motion_planning", - "obstacle_cruise_planner", - "obstacle_cruise_planner.param.yaml", - ) - with open(obstacle_cruise_planner_param_path, "r") as f: - obstacle_cruise_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] - obstacle_cruise_planner_component = ComposableNode( - package="obstacle_cruise_planner", - plugin="motion_planning::ObstacleCruisePlannerNode", - name="obstacle_cruise_planner", - namespace="", - remappings=[ - ("~/input/trajectory", "obstacle_velocity_limiter/trajectory"), - ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/acceleration", "/localization/acceleration"), - ("~/input/objects", "/perception/object_recognition/objects"), - ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), - ("~/output/velocity_limit", "/planning/scenario_planning/max_velocity_candidates"), - ("~/output/clear_velocity_limit", "/planning/scenario_planning/clear_velocity_limit"), - ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), - ], - parameters=[ - common_param, - nearest_search_param, - obstacle_cruise_planner_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # obstacle stop planner - obstacle_stop_planner_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "motion_planning", - "obstacle_stop_planner", - "obstacle_stop_planner.param.yaml", - ) - obstacle_stop_planner_acc_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "lane_driving", - "motion_planning", - "obstacle_stop_planner", - "adaptive_cruise_control.param.yaml", - ) - with open(obstacle_stop_planner_param_path, "r") as f: - obstacle_stop_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] - with open(obstacle_stop_planner_acc_param_path, "r") as f: - obstacle_stop_planner_acc_param = yaml.safe_load(f)["/**"]["ros__parameters"] - obstacle_stop_planner_component = ComposableNode( - package="obstacle_stop_planner", - plugin="motion_planning::ObstacleStopPlannerNode", - name="obstacle_stop_planner", - namespace="", - remappings=[ - ("~/output/stop_reason", "/planning/scenario_planning/status/stop_reason"), - ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), - ("~/output/max_velocity", "/planning/scenario_planning/max_velocity_candidates"), - ( - "~/output/velocity_limit_clear_command", - "/planning/scenario_planning/clear_velocity_limit", - ), - ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), - ("~/input/acceleration", "/localization/acceleration"), - ( - "~/input/pointcloud", - "/perception/obstacle_segmentation/pointcloud", - ), - ("~/input/objects", "/perception/object_recognition/objects"), - ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/trajectory", "obstacle_velocity_limiter/trajectory"), - ], - parameters=[ - common_param, - nearest_search_param, - obstacle_stop_planner_param, - obstacle_stop_planner_acc_param, - {"enable_slow_down": False}, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - obstacle_cruise_planner_relay_component = ComposableNode( - package="topic_tools", - plugin="topic_tools::RelayNode", - name="obstacle_cruise_planner_relay", - namespace="", - parameters=[ - {"input_topic": "obstacle_velocity_limiter/trajectory"}, - {"output_topic": "/planning/scenario_planning/lane_driving/trajectory"}, - {"type": "autoware_auto_planning_msgs/msg/Trajectory"}, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - container = ComposableNodeContainer( - name="motion_planning_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[ - obstacle_avoidance_planner_component, - obstacle_velocity_limiter_component, - ], - ) - - obstacle_stop_planner_loader = LoadComposableNodes( - composable_node_descriptions=[obstacle_stop_planner_component], - target_container=container, - condition=LaunchConfigurationEquals("cruise_planner_type", "obstacle_stop_planner"), - ) - - obstacle_cruise_planner_loader = LoadComposableNodes( - composable_node_descriptions=[obstacle_cruise_planner_component], - target_container=container, - condition=LaunchConfigurationEquals("cruise_planner_type", "obstacle_cruise_planner"), - ) - - obstacle_cruise_planner_relay_loader = LoadComposableNodes( - composable_node_descriptions=[obstacle_cruise_planner_relay_component], - target_container=container, - condition=LaunchConfigurationEquals("cruise_planner_type", "none"), - ) - - surround_obstacle_checker_loader = LoadComposableNodes( - composable_node_descriptions=[surround_obstacle_checker_component], - target_container=container, - condition=IfCondition(LaunchConfiguration("use_surround_obstacle_check")), - ) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - return launch.LaunchDescription( - launch_arguments - + [ - DeclareLaunchArgument( - "input_path_topic", - default_value="/planning/scenario_planning/lane_driving/behavior_planning/path", - ), - DeclareLaunchArgument("use_surround_obstacle_check", default_value="true"), - DeclareLaunchArgument("use_intra_process", default_value="false"), - DeclareLaunchArgument("use_multithread", default_value="false"), - set_container_executable, - set_container_mt_executable, - container, - surround_obstacle_checker_loader, - obstacle_stop_planner_loader, - obstacle_cruise_planner_loader, - obstacle_cruise_planner_relay_loader, - ] - ) 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 deleted file mode 100644 index de101a8040..0000000000 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ /dev/null @@ -1,40 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/planning_launch/launch/scenario_planning/parking.launch.py b/planning_launch/launch/scenario_planning/parking.launch.py deleted file mode 100644 index e3d9e750a0..0000000000 --- a/planning_launch/launch/scenario_planning/parking.launch.py +++ /dev/null @@ -1,137 +0,0 @@ -# Copyright 2021 Tier IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import os - -from ament_index_python.packages import get_package_share_directory -import launch -from launch.actions import DeclareLaunchArgument -from launch.actions import GroupAction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import PushRosNamespace -from launch_ros.descriptions import ComposableNode -import yaml - - -def generate_launch_description(): - freespace_planner_param_path = os.path.join( - get_package_share_directory("planning_launch"), - "config", - "scenario_planning", - "parking", - "freespace_planner", - "freespace_planner.param.yaml", - ) - with open(freespace_planner_param_path, "r") as f: - freespace_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - container = ComposableNodeContainer( - name="parking_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[ - ComposableNode( - package="costmap_generator", - plugin="CostmapGenerator", - name="costmap_generator", - remappings=[ - ("~/input/objects", "/perception/object_recognition/objects"), - ( - "~/input/points_no_ground", - "/perception/obstacle_segmentation/pointcloud", - ), - ("~/input/vector_map", "/map/vector_map"), - ("~/input/scenario", "/planning/scenario_planning/scenario"), - ("~/output/grid_map", "costmap_generator/grid_map"), - ("~/output/occupancy_grid", "costmap_generator/occupancy_grid"), - ], - parameters=[ - { - "costmap_frame": "map", - "vehicle_frame": "base_link", - "map_frame": "map", - "update_rate": 10.0, - "use_wayarea": True, - "use_objects": True, - "use_points": True, - "grid_min_value": 0.0, - "grid_max_value": 1.0, - "grid_resolution": 0.2, - "grid_length_x": 70.0, - "grid_length_y": 70.0, - "grid_position_x": 0.0, - "grid_position_y": 0.0, - "maximum_lidar_height_thres": 0.3, - "minimum_lidar_height_thres": -2.2, - "expand_polygon_size": 1.0, - "size_of_expansion_kernel": 9, - }, - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ), - ComposableNode( - package="freespace_planner", - plugin="freespace_planner::FreespacePlannerNode", - name="freespace_planner", - remappings=[ - ("~/input/route", "/planning/mission_planning/route"), - ("~/input/occupancy_grid", "costmap_generator/occupancy_grid"), - ("~/input/scenario", "/planning/scenario_planning/scenario"), - ("~/input/odometry", "/localization/kinematic_state"), - ("~/output/trajectory", "/planning/scenario_planning/parking/trajectory"), - ("is_completed", "/planning/scenario_planning/parking/is_completed"), - ], - parameters=[ - freespace_planner_param, - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ), - ], - ) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - return launch.LaunchDescription( - [ - DeclareLaunchArgument( - "use_intra_process", - default_value="false", - description="use ROS2 component container communication", - ), - DeclareLaunchArgument( - "use_multithread", default_value="false", description="use multithread" - ), - set_container_executable, - set_container_mt_executable, - GroupAction([PushRosNamespace("parking"), container]), - ] - ) diff --git a/planning_launch/launch/scenario_planning/parking.launch.xml b/planning_launch/launch/scenario_planning/parking.launch.xml deleted file mode 100644 index 9fbf153549..0000000000 --- a/planning_launch/launch/scenario_planning/parking.launch.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml deleted file mode 100644 index fc06076d5a..0000000000 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ /dev/null @@ -1,57 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/planning_launch/package.xml b/planning_launch/package.xml deleted file mode 100644 index e8e473ca5d..0000000000 --- a/planning_launch/package.xml +++ /dev/null @@ -1,31 +0,0 @@ - - - planning_launch - 0.1.0 - The planning_launch package - - Takamasa Horibe - - Apache License 2.0 - - ament_cmake_auto - - behavior_velocity_planner - costmap_generator - external_velocity_limit_selector - freespace_planner - mission_planner - motion_velocity_smoother - obstacle_avoidance_planner - obstacle_stop_planner - obstacle_velocity_limiter - scenario_selector - surround_obstacle_checker - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/planning_launch/planning_launch.drawio.svg b/planning_launch/planning_launch.drawio.svg deleted file mode 100644 index fba2aefed5..0000000000 --- a/planning_launch/planning_launch.drawio.svg +++ /dev/null @@ -1,318 +0,0 @@ - - - - - - - -
    -
    -
    - planning.launch.xml -
    -
    -
    - - package: planning_launch - -
    -
    -
    -
    -
    - - planning.launch.xml... - -
    -
    - - - - -
    -
    -
    - mission_planning.launch.py -
    -
    -
    - package: planning_launch -
    -
    -
    -
    -
    - - mission_planning.launch.py... - -
    -
    - - - - - - - - -
    -
    -
    - launch name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - launch name... - -
    -
    - - - - -
    -
    -
    - ex: -
    -
    -
    -
    - - ex: - -
    -
    - - - - -
    -
    -
    - node name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - node name... - -
    -
    - - - - -
    -
    -
    - other name -
    -
    -
    - - package: package name - -
    -
    -
    -
    -
    - - other name... - -
    -
    - - - - -
    -
    -
    - scenario_planning.launch.xml -
    -
    -
    - package: planning_launch -
    -
    -
    -
    -
    - - scenario_planning.launch.xml... - -
    -
    - - - - -
    -
    -
    - mission_planner.launch.xml -
    -
    -
    - package: mission_planner -
    -
    -
    -
    -
    - - mission_planner.launch.xml... - -
    -
    - - - - -
    -
    -
    - goal_pose_visualizer.launch.xml -
    -
    -
    - package: mission_planner -
    -
    -
    -
    -
    - - goal_pose_visualizer.launch.xml... - -
    -
    - - - - - - - - -
    -
    -
    - scenario_selector.launch.xml -
    -
    -
    - package: scenario_selector -
    -
    -
    -
    -
    - - scenario_selector.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - motion_velocity_optimizer.launch.xml -
    -
    -
    - package: motion_velocity_optimizer -
    -
    -
    -
    -
    - - motion_velocity_optimizer.launch.xml... - -
    -
    - - - - - - -
    -
    -
    - lane_driving.launch.xml -
    -
    -
    - package: planning_launch -
    -
    -
    -
    -
    - - lane_driving.launch.xml... - -
    -
    - - - - -
    -
    -
    - parking.launch.py -
    -
    -
    - package: planning_launch -
    -
    -
    -
    -
    - - parking.launch.py... - -
    -
    - - - - -
    - - - - - Viewer does not support full SVG 1.1 - - - -
    \ No newline at end of file From 0bd58cb79386c01b47ef2260261550618dc304d2 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 20 Jan 2023 13:13:15 +0900 Subject: [PATCH 758/851] fix(lane_change): default parameter revert (#714) --- .../behavior_path_planner/behavior_path_planner.param.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index 055cec3acb..7a6bd05976 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -27,8 +27,8 @@ expected_front_deceleration: -1.0 expected_rear_deceleration: -1.0 - expected_front_deceleration_for_abort: -2.0 - expected_rear_deceleration_for_abort: -2.5 + expected_front_deceleration_for_abort: -1.0 + expected_rear_deceleration_for_abort: -2.0 rear_vehicle_reaction_time: 2.0 - rear_vehicle_safety_time_margin: 1.0 + rear_vehicle_safety_time_margin: 2.0 From fefef1fb07ec43fd552c9f9f5ef045c246984f56 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 20 Jan 2023 13:15:48 +0900 Subject: [PATCH 759/851] fix(autoware_launch): change planning parameters (#715) Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../motion_velocity_smoother.param.yaml | 2 +- .../behavior_path_planner/pull_out/pull_out.param.yaml | 4 ++-- .../behavior_path_planner/pull_over/pull_over.param.yaml | 8 +++++--- 3 files changed, 8 insertions(+), 6 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index 64b2d95c6f..9534a87fc5 100644 --- a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -9,7 +9,7 @@ # curve parameters max_lateral_accel: 1.0 # max lateral acceleration limit [m/ss] - min_curve_velocity: 0.5 # min velocity at lateral acceleration limit and steering angle rate limit [m/s] + min_curve_velocity: 2.74 # min velocity at lateral acceleration limit and steering angle rate 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 min_decel_for_lateral_acc_lim_filter: -2.5 # deceleration limit applied in the lateral acceleration filter to avoid sudden braking [m/ss] diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml index 9fcbc2a173..68000747b7 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml @@ -5,18 +5,18 @@ th_stopped_velocity: 0.01 th_stopped_time: 1.0 collision_check_margin: 1.0 - pull_out_finish_judge_buffer: 1.0 + collision_check_distance_from_end: 1.0 # shift pull out enable_shift_pull_out: true shift_pull_out_velocity: 2.0 pull_out_sampling_num: 4 - before_pull_out_straight_distance: 0.0 minimum_shift_pull_out_distance: 20.0 maximum_lateral_jerk: 2.0 minimum_lateral_jerk: 0.5 deceleration_interval: 15.0 # geometric pull out enable_geometric_pull_out: true + divide_pull_out_path: false geometric_pull_out_velocity: 1.0 arc_path_interval: 1.0 lane_departure_margin: 0.2 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index 44d859a477..f09439edf7 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: pull_over: - request_length: 200.0 + request_length: 100.0 th_arrived_distance: 1.0 th_stopped_velocity: 0.01 th_stopped_time: 2.0 # It must be greater than the state_machine's. @@ -17,6 +17,9 @@ backward_goal_search_length: 20.0 goal_search_interval: 2.0 longitudinal_margin: 3.0 + max_lateral_offset: 0.5 + lateral_offset_interval: 0.25 + ignore_distance_from_lane_start: 15.0 # occupancy grid map use_occupancy_grid: true use_occupancy_grid_for_longitudinal_margin: false @@ -32,8 +35,7 @@ maximum_lateral_jerk: 2.0 minimum_lateral_jerk: 0.5 deceleration_interval: 15.0 - after_pull_over_straight_distance: 5.0 - before_pull_over_straight_distance: 5.0 + after_pull_over_straight_distance: 1.0 # parallel parking path enable_arc_forward_parking: true enable_arc_backward_parking: true From c648bd501969830cc2d0c57e793b6e0a25d87e67 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 20 Jan 2023 14:31:07 +0900 Subject: [PATCH 760/851] ci: add sync-awf-autoware-launch (#717) * ci: add sync-awf-autoware-launch Signed-off-by: kminoda * update sync workflow name Signed-off-by: kminoda Signed-off-by: kminoda --- .../workflows/sync-awf-autoware-launch.yaml | 31 +++++++++++++++++++ 1 file changed, 31 insertions(+) create mode 100644 .github/workflows/sync-awf-autoware-launch.yaml diff --git a/.github/workflows/sync-awf-autoware-launch.yaml b/.github/workflows/sync-awf-autoware-launch.yaml new file mode 100644 index 0000000000..3bf43c6c21 --- /dev/null +++ b/.github/workflows/sync-awf-autoware-launch.yaml @@ -0,0 +1,31 @@ +name: sync-awf-autoware-launch + +on: + schedule: + - cron: 0 0 * * * + workflow_dispatch: + +jobs: + sync-awf-latest: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + base-branch: awf-latest + sync-pr-branch: sync-awf-autoware-launch + sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git + sync-target-branch: main + pr-title: "chore: sync awf/autoware_launch" + pr-labels: | + bot + sync-awf-autoware-launch + auto-merge-method: merge From ffe7c90707c42225d9a7c12c82e3c166bcf9ec4e Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 20 Jan 2023 18:19:48 +0900 Subject: [PATCH 761/851] feat(planning_validator): add planning_validator pkg (#675) * update Signed-off-by: Takamasa Horibe * update Signed-off-by: Takamasa Horibe Signed-off-by: Takamasa Horibe --- .../planning_validator.param.yaml | 28 +++++++++++++++++++ .../tier4_planning_component.launch.xml | 3 ++ 2 files changed, 31 insertions(+) create mode 100644 autoware_launch/config/planning/scenario_planning/common/planning_validator/planning_validator.param.yaml diff --git a/autoware_launch/config/planning/scenario_planning/common/planning_validator/planning_validator.param.yaml b/autoware_launch/config/planning/scenario_planning/common/planning_validator/planning_validator.param.yaml new file mode 100644 index 0000000000..658a968906 --- /dev/null +++ b/autoware_launch/config/planning/scenario_planning/common/planning_validator/planning_validator.param.yaml @@ -0,0 +1,28 @@ +/**: + ros__parameters: + # Operation option when invalid trajectory is detected + # 0: publish the trajectory even if it is invalid + # 1: stop publishing the trajectory + # 2: publish the last validated trajectory + invalid_trajectory_handling_type: 0 + + publish_diag: true # if true, diagnostic msg is published + + # If the number of consecutive invalid trajectory exceeds this threshold, the Diag will be set to ERROR. + # (For example, threshold = 1 means, even if the trajectory is invalid, Diag will not be ERROR if + # the next trajectory is valid.) + diag_error_count_threshold: 0 + + display_on_terminal: true # show error msg on terminal + + thresholds: + interval: 100.0 + relative_angle: 2.0 # (= 115 degree) + curvature: 1.0 + lateral_acc: 9.8 + longitudinal_max_acc: 9.8 + longitudinal_min_acc: -9.8 + steering: 1.414 + steering_rate: 10.0 + velocity_deviation: 100.0 + distance_deviation: 100.0 diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml index b0ee0489ba..fb8b94083f 100644 --- a/autoware_launch/launch/components/tier4_planning_component.launch.xml +++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml @@ -119,5 +119,8 @@ + + +
    From 2bc3e68f6fa0877c633d30647d2a67424524ff09 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 21 Jan 2023 12:32:13 +0900 Subject: [PATCH 762/851] fix(autoware_launch): fix smoother type (#726) Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../launch/components/tier4_planning_component.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml index fb8b94083f..07dc260100 100644 --- a/autoware_launch/launch/components/tier4_planning_component.launch.xml +++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml @@ -54,7 +54,7 @@ /> - + - + From 46b45280bb07090280d4efe96a8f4a8b40006bc8 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 23 Jan 2023 09:46:14 +0900 Subject: [PATCH 763/851] ci: fix sync-awf-autoware-launch workflow (#721) Signed-off-by: kminoda Signed-off-by: kminoda --- .github/workflows/sync-awf-autoware-launch.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/sync-awf-autoware-launch.yaml b/.github/workflows/sync-awf-autoware-launch.yaml index 3bf43c6c21..d1fd166e87 100644 --- a/.github/workflows/sync-awf-autoware-launch.yaml +++ b/.github/workflows/sync-awf-autoware-launch.yaml @@ -6,7 +6,7 @@ on: workflow_dispatch: jobs: - sync-awf-latest: + sync-awf-autoware-launch: runs-on: ubuntu-latest steps: - name: Generate token From 2792ce13ac464c63f7e4f21ef42f1ce24606c04e Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 23 Jan 2023 10:05:47 +0900 Subject: [PATCH 764/851] fix(planning_launch): rename parameter for obstacle stop planner (#711) fix(planning_launch): hunting -> chattering Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- .../obstacle_stop_planner/obstacle_stop_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml index 8954a46ab1..93f9d522fb 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml @@ -1,6 +1,6 @@ /**: ros__parameters: - hunting_threshold: 0.5 # even if the obstacle disappears, the stop judgment continues for hunting_threshold [s] + chattering_threshold: 0.5 # even if the obstacle disappears, the stop judgment continues for chattering_threshold [s] lowpass_gain: 0.9 # gain parameter for low pass filter [-] max_velocity: 20.0 # max velocity [m/s] enable_slow_down: False # whether to use slow down planner [-] From 8e63e49778f37e3bd30b0bea5110536256c42449 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Mon, 23 Jan 2023 16:02:31 +0900 Subject: [PATCH 765/851] feat(behavior_path_planner): external request lane change (#691) * feat(autoware_launch): visualize multiple candidate paths Signed-off-by: Fumiya Watanabe * feature(autoware_launch): fix name space in autoware.rviz Signed-off-by: Fumiya Watanabe * feat(planning_launch) fix params for external request lane change Signed-off-by: Fumiya Watanabe * fix(autoware.rviz): remove unnecessary configurations Signed-off-by: Fumiya Watanabe Signed-off-by: Fumiya Watanabe --- .../rtc_auto_mode_manager.param.yaml | 2 ++ autoware_launch/rviz/autoware.rviz | 35 +++++++++++++++---- 2 files changed, 31 insertions(+), 6 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml index 8ba0a402ee..0e3391e69e 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml @@ -7,6 +7,8 @@ - "intersection" - "no_stopping_area" - "traffic_light" + - "ext_request_lane_change_left" + - "ext_request_lane_change_right" - "lane_change_left" - "lane_change_right" - "avoidance_left" diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index d32fe7d3d5..78dc8d3fcb 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1036,13 +1036,13 @@ Visualization Manager: - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true - Name: PathChangeCandidate_Avoidance + Name: PathChangeCandidate_ExternalRequestLaneChangeRight Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/path_candidate/avoidance + Value: /planning/path_candidate/ext_request_lane_change_right Value: true View Path: Alpha: 0.30000001192092896 @@ -1059,13 +1059,13 @@ Visualization Manager: - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true - Name: PathChangeCandidate_PullOut + Name: PathChangeCandidate_ExternalRequestLaneChangeLeft Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/path_candidate/pull_out + Value: /planning/path_candidate/ext_request_lane_change_left Value: true View Path: Alpha: 0.30000001192092896 @@ -1082,13 +1082,36 @@ Visualization Manager: - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true - Name: PathChangeCandidate_PullOver + Name: PathChangeCandidate_Avoidance Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/path_candidate/pull_over + Value: /planning/path_candidate/avoidance + Value: true + View Path: + Alpha: 0.30000001192092896 + Color: 115; 210; 22 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 0.30000001192092896 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false + - Class: rviz_plugins/Path + Color Border Vel Max: 3 + Enabled: true + Name: PathChangeCandidate_PullOut + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/path_candidate/pull_out Value: true View Path: Alpha: 0.30000001192092896 From fe156a5268c39e2659cee7a3fbdf3a710343ad23 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 24 Jan 2023 20:45:30 +0900 Subject: [PATCH 766/851] feat(autoware_launch): visualize modified_goal as PoseWithUuidStamped (#732) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- autoware_launch/rviz/autoware.rviz | 16 ++++++---------- 1 file changed, 6 insertions(+), 10 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 78dc8d3fcb..4fe3b9cd80 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1775,18 +1775,11 @@ Visualization Manager: Value: true Enabled: true Name: Parking - - Alpha: 1 - Axes Length: 1 - Axes Radius: 0.30000001192092896 - Class: rviz_default_plugins/Pose - Color: 255; 25; 0 + - Class: rviz_plugins/PoseWithUuidStamped Enabled: true - Head Length: 0.30000001192092896 - Head Radius: 0.10000000149011612 + Length: 1.5 Name: ModifiedGoal - Shaft Length: 1 - Shaft Radius: 0.05000000074505806 - Shape: Axes + Radius: 0.5 Topic: Depth: 5 Durability Policy: Volatile @@ -1794,6 +1787,9 @@ Visualization Manager: History Policy: Keep Last Reliability Policy: Reliable Value: /planning/scenario_planning/modified_goal + UUID: + Scale: 0.30000001192092896 + Value: false Value: true Enabled: true Name: ScenarioPlanning From 13b3a38a080a024ef41402fa4feb8c6e40989ba9 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 24 Jan 2023 20:46:21 +0900 Subject: [PATCH 767/851] fix(lane change): adaptive safety check time parameters (#734) --- .../behavior_path_planner/behavior_path_planner.param.yaml | 2 +- .../behavior_path_planner/lane_change/lane_change.param.yaml | 5 ++--- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index 7a6bd05976..3e70681dbd 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -31,4 +31,4 @@ expected_rear_deceleration_for_abort: -2.0 rear_vehicle_reaction_time: 2.0 - rear_vehicle_safety_time_margin: 2.0 + rear_vehicle_safety_time_margin: 1.0 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml index 41de868418..c25eb73d62 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -2,7 +2,6 @@ ros__parameters: lane_change: lane_change_prepare_duration: 4.0 # [s] - lane_changing_safety_check_duration: 8.0 # [s] minimum_lane_change_prepare_distance: 2.0 # [m] minimum_lane_change_length: 16.5 # [m] @@ -18,9 +17,9 @@ lane_change_sampling_num: 10 # collision check - enable_collision_check_at_prepare_phase: true + enable_collision_check_at_prepare_phase: false prepare_phase_ignore_target_speed_thresh: 0.1 # [m/s] - use_predicted_path_outside_lanelet: true + use_predicted_path_outside_lanelet: false use_all_predicted_path: false # abort From 58678b96d1a302c438a6550b0f2b9130e1b51040 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 24 Jan 2023 23:07:31 +0900 Subject: [PATCH 768/851] feat(intersection): consider state transit margin time in collision detection (#728) Signed-off-by: Mamoru Sobue --- .../behavior_velocity_planner/intersection.param.yaml | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index 220c087d18..a769848497 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -1,10 +1,8 @@ /**: ros__parameters: intersection: - state_transit_margin_time: 0.5 + state_transit_margin_time: 1.0 stop_line_margin: 3.0 - keep_detection_line_margin: 1.0 # distance (toward path end) from generated stop line. keep detection if ego is before this line and ego.vel < keep_detection_vel_thr - keep_detection_vel_thr: 0.833 # == 3.0km/h stuck_vehicle_detect_dist: 3.0 # this should be the length between cars when they are stopped. The actual stuck vehicle detection length will be this value + vehicle_length. stuck_vehicle_ignore_dist: 10.0 # obstacle stop max distance(5.0m) + stuck vehicle size / 2 (0.0m-) stuck_vehicle_vel_thr: 0.833 # 0.833m/s = 3.0km/h @@ -16,8 +14,9 @@ detection_area_length: 200.0 # [m] detection_area_angle_threshold: 0.785 # [rad] min_predicted_path_confidence: 0.05 - collision_start_margin_time: 5.0 # [s] - collision_end_margin_time: 2.0 # [s] + minimum_ego_predicted_velocity: 1.388 # [m/s] + collision_start_margin_time: 4.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object + collision_end_margin_time: 6.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object use_stuck_stopline: false # stopline generate before the intersection lanelet when is_stuck assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of front car when front car as well as ego are turning enable_front_car_decel_prediction: false # By default this feature is disabled From 9a20d12957b01460d07e388acb291d468cba1143 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 24 Jan 2023 23:35:45 +0900 Subject: [PATCH 769/851] feat(control_launch): add min_braking_distance to lane_departure_checker (#736) feat(control_launch): add min_braking_distance to lane departure_checker Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../lane_departure_checker/lane_departure_checker.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml index 092a6765aa..9512ed388d 100644 --- a/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml +++ b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml @@ -13,3 +13,4 @@ max_longitudinal_deviation: 2.0 max_yaw_deviation_deg: 60.0 delta_yaw_threshold_for_closest_point: 1.570 #M_PI/2.0, delta yaw thres for closest point + min_braking_distance: 0.0 From 111cf030d9ab5a46f8b5e2bafa17159fdfbdbd42 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 25 Jan 2023 10:09:46 +0900 Subject: [PATCH 770/851] refactor(autoware_launch): add map_component launcher (#731) * feat(autoware_launch): add map_component launcher Signed-off-by: kminoda * added lanelet2 parameter too Signed-off-by: kminoda * revert the addition of lanelet2 param Signed-off-by: kminoda Signed-off-by: kminoda --- .../config/map/pointcloud_map_loader.param.yaml | 9 +++++++++ autoware_launch/launch/autoware.launch.xml | 2 +- .../launch/components/tier4_map_component.launch.xml | 12 ++++++++++++ 3 files changed, 22 insertions(+), 1 deletion(-) create mode 100644 autoware_launch/config/map/pointcloud_map_loader.param.yaml create mode 100644 autoware_launch/launch/components/tier4_map_component.launch.xml diff --git a/autoware_launch/config/map/pointcloud_map_loader.param.yaml b/autoware_launch/config/map/pointcloud_map_loader.param.yaml new file mode 100644 index 0000000000..8f3ccbff00 --- /dev/null +++ b/autoware_launch/config/map/pointcloud_map_loader.param.yaml @@ -0,0 +1,9 @@ +/**: + ros__parameters: + enable_whole_load: true + enable_downsampled_whole_load: false + enable_partial_load: false + enable_differential_load: false + + # only used when downsample_whole_load enabled + leaf_size: 3.0 # downsample leaf size [m] diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index c848c487a6..45155cfe86 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -73,7 +73,7 @@ - + diff --git a/autoware_launch/launch/components/tier4_map_component.launch.xml b/autoware_launch/launch/components/tier4_map_component.launch.xml new file mode 100644 index 0000000000..cba9c3c0a2 --- /dev/null +++ b/autoware_launch/launch/components/tier4_map_component.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + From 21ecce91ea9d8693cd8ab57359862dcba22b6774 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 27 Jan 2023 14:05:26 +0900 Subject: [PATCH 771/851] feat(intersection): add param for overshoot from stop line (#738) Signed-off-by: Mamoru Sobue --- .../behavior_velocity_planner/intersection.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index a769848497..9ed153bb1c 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -20,6 +20,7 @@ use_stuck_stopline: false # stopline generate before the intersection lanelet when is_stuck assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of front car when front car as well as ego are turning enable_front_car_decel_prediction: false # By default this feature is disabled + stop_overshoot_margin: 0.5 # [m] overshoot margin for stuck, collsion detection merge_from_private_road: stop_duration_sec: 1.0 From 1e4ead728dc515b933222d0aedefcf490bc22d60 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 27 Jan 2023 21:10:27 +0900 Subject: [PATCH 772/851] feat(mpc_lateral_controller): add steering bias removal (#735) * feat(mpc_lateral_controller): add steering bias removal Signed-off-by: Takamasa Horibe * change name Signed-off-by: Takamasa Horibe Signed-off-by: Takamasa Horibe --- .../control/trajectory_follower/lateral/mpc.param.yaml | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml index 4b4f348a5a..2324976f49 100644 --- a/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml +++ b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml @@ -63,6 +63,14 @@ new_traj_duration_time: 1.0 new_traj_end_dist: 0.3 + # steer offset + steering_offset: + enable_auto_steering_offset_removal: true + update_vel_threshold: 5.56 + update_steer_threshold: 0.035 + average_num: 1000 + steering_offset_limit: 0.02 + # vehicle parameters vehicle: cg_to_front_m: 1.228 From 799f97b0f596d46dfc89a3ff253011c84d089191 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 30 Jan 2023 14:43:17 +0900 Subject: [PATCH 773/851] ci(pre-commit): autoupdate (#694) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit updates: - [github.com/igorshubovych/markdownlint-cli: v0.32.2 → v0.33.0](https://github.com/igorshubovych/markdownlint-cli/compare/v0.32.2...v0.33.0) - [github.com/adrienverge/yamllint: v1.28.0 → v1.29.0](https://github.com/adrienverge/yamllint/compare/v1.28.0...v1.29.0) - [github.com/tier4/pre-commit-hooks-ros: v0.7.1 → v0.8.0](https://github.com/tier4/pre-commit-hooks-ros/compare/v0.7.1...v0.8.0) - [github.com/shellcheck-py/shellcheck-py: v0.8.0.4 → v0.9.0.2](https://github.com/shellcheck-py/shellcheck-py/compare/v0.8.0.4...v0.9.0.2) - [github.com/scop/pre-commit-shfmt: v3.5.1-1 → v3.6.0-1](https://github.com/scop/pre-commit-shfmt/compare/v3.5.1-1...v3.6.0-1) - [github.com/pycqa/isort: 5.10.1 → 5.11.4](https://github.com/pycqa/isort/compare/5.10.1...5.11.4) - [github.com/psf/black: 22.10.0 → 22.12.0](https://github.com/psf/black/compare/22.10.0...22.12.0) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .pre-commit-config.yaml | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index bb390fbd4a..92bf280463 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -18,7 +18,7 @@ repos: args: [--markdown-linebreak-ext=md] - repo: https://github.com/igorshubovych/markdownlint-cli - rev: v0.32.2 + rev: v0.33.0 hooks: - id: markdownlint args: [-c, .markdownlint.yaml, --fix] @@ -29,35 +29,35 @@ repos: - id: prettier - repo: https://github.com/adrienverge/yamllint - rev: v1.28.0 + rev: v1.29.0 hooks: - id: yamllint - repo: https://github.com/tier4/pre-commit-hooks-ros - rev: v0.7.1 + rev: v0.8.0 hooks: - id: flake8-ros - id: prettier-package-xml - id: sort-package-xml - repo: https://github.com/shellcheck-py/shellcheck-py - rev: v0.8.0.4 + rev: v0.9.0.2 hooks: - id: shellcheck - repo: https://github.com/scop/pre-commit-shfmt - rev: v3.5.1-1 + rev: v3.6.0-1 hooks: - id: shfmt args: [-w, -s, -i=4] - repo: https://github.com/pycqa/isort - rev: 5.10.1 + rev: 5.11.4 hooks: - id: isort - repo: https://github.com/psf/black - rev: 22.10.0 + rev: 22.12.0 hooks: - id: black args: [--line-length=100] From 6787f769c54c12b94d7e3ed57842077b363a1371 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Mon, 30 Jan 2023 14:49:17 +0900 Subject: [PATCH 774/851] ci: upgrade isort version (#739) Signed-off-by: Tomohito Ando --- .pre-commit-config.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 92bf280463..d04c26073e 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -52,7 +52,7 @@ repos: args: [-w, -s, -i=4] - repo: https://github.com/pycqa/isort - rev: 5.11.4 + rev: 5.12.0 hooks: - id: isort From cc47677ac0cdca7050ad4709dc183bd3f5a9ee03 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 1 Feb 2023 16:53:21 +0900 Subject: [PATCH 775/851] fix(occlusion_spot): occlusion spot parameter disable as default (#741) Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_velocity_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml index 7aab0af21f..ff51b6e37a 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml @@ -7,7 +7,7 @@ launch_blind_spot: true launch_detection_area: true launch_virtual_traffic_light: true - launch_occlusion_spot: true + launch_occlusion_spot: false launch_no_stopping_area: true launch_run_out: false launch_speed_bump: false From 2e8ddda837abb1bd3e5403c3da5ba9f1e7c04f9e Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Thu, 2 Feb 2023 16:33:54 +0900 Subject: [PATCH 776/851] chore: sync awf/autoware_launch (#737) * feat(autoware_launch): visualize modified_goal as PoseWithUuidStamped (#182) Signed-off-by: kosuke55 Signed-off-by: kosuke55 * feat(intersection): improve ego velocity prediction in collision detection (#181) Signed-off-by: Mamoru Sobue * feat(control_launch): add min_braking_distance to lane_departure_checker (#184) Signed-off-by: kosuke55 * fix(autoware_launch): enable launch_deprecated_api (#187) * fix(autoware_launch): enable launch_deprecated_api Signed-off-by: Takayuki Murooka * Update autoware_launch/launch/components/tier4_autoware_api_component.launch.xml Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> Signed-off-by: Takayuki Murooka Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> * fix(behavior_path_planner): prevent pull out back twice (#176) Signed-off-by: kosuke55 Signed-off-by: kosuke55 * feat(intersection): add param for stuck stopline overshoot margin (#188) Signed-off-by: Mamoru Sobue * feat(mpc_lateral_controller): add steering bias removal (#190) * feat(mpc_lateral_controller): add steering bias removal Signed-off-by: Takamasa Horibe * change name Signed-off-by: Takamasa Horibe Signed-off-by: Takamasa Horibe * feat: remove unused args Signed-off-by: Takagi, Isamu --------- Signed-off-by: kosuke55 Signed-off-by: Mamoru Sobue Signed-off-by: Takayuki Murooka Signed-off-by: Takamasa Horibe Signed-off-by: tomoya.kimura Signed-off-by: Takagi, Isamu Co-authored-by: Kosuke Takeuchi Co-authored-by: Mamoru Sobue Co-authored-by: Takayuki Murooka Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> Co-authored-by: Takamasa Horibe Co-authored-by: tomoya.kimura Co-authored-by: Takagi, Isamu --- .../launch/components/tier4_autoware_api_component.launch.xml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml b/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml index ccc1527fb0..4fdacc2656 100644 --- a/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml +++ b/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml @@ -1,5 +1,6 @@ + - + From 123e419d0279efd8f3ae38aafeb59a9210a5ef70 Mon Sep 17 00:00:00 2001 From: asana17 Date: Fri, 3 Feb 2023 13:21:33 +0900 Subject: [PATCH 777/851] move system_launch to autoware_launch --- .../component_state_monitor/topics.yaml | 0 .../diagnostic_aggregator/system.param.yaml | 0 .../diagnostic_aggregator/vehicle.param.yaml | 0 .../dummy_diag_publisher.param.yaml | 49 +++++++++++ .../emergency_handler.param.yaml | 0 .../mrm_comfortable_stop_operator.param.yaml | 0 .../mrm_emergency_stop_operator.param.yaml | 0 .../system_error_monitor.param.yaml | 0 ...ror_monitor.planning_simulation.param.yaml | 0 .../system_monitor/cpu_monitor.param.yaml | 0 .../system_monitor/gpu_monitor.param.yaml | 0 .../system_monitor/hdd_monitor.param.yaml | 0 .../system_monitor/mem_monitor.param.yaml | 0 .../system_monitor/net_monitor.param.yaml | 0 .../system_monitor/ntp_monitor.param.yaml | 0 .../system_monitor/process_monitor.param.yaml | 0 .../system_monitor/voltage_monitor.param.yaml | 0 autoware_launch/launch/autoware.launch.xml | 2 +- .../tier4_system_component.launch.xml | 29 +++++++ autoware_launch/package.xml | 7 +- .../system_launch.drawio.svg | 0 system_launch/CMakeLists.txt | 20 ----- system_launch/README.md | 17 ---- .../config/system_error_monitor.param.yaml | 52 ----------- .../dummy_diag_publisher/control.launch.xml | 7 -- .../localization.launch.xml | 11 --- .../dummy_diag_publisher/system.launch.xml | 87 ------------------- .../dummy_diag_publisher/vehicle.launch.xml | 7 -- system_launch/launch/system.launch.xml | 84 ------------------ system_launch/package.xml | 24 ----- 30 files changed, 85 insertions(+), 311 deletions(-) rename {system_launch/config => autoware_launch/config/system}/component_state_monitor/topics.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/diagnostic_aggregator/system.param.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/diagnostic_aggregator/vehicle.param.yaml (100%) create mode 100644 autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml rename {system_launch/config => autoware_launch/config/system}/emergency_handler/emergency_handler.param.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator.param.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/mrm_emergency_stop_operator/mrm_emergency_stop_operator.param.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/system_error_monitor/system_error_monitor.param.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/system_error_monitor/system_error_monitor.planning_simulation.param.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/system_monitor/cpu_monitor.param.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/system_monitor/gpu_monitor.param.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/system_monitor/hdd_monitor.param.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/system_monitor/mem_monitor.param.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/system_monitor/net_monitor.param.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/system_monitor/ntp_monitor.param.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/system_monitor/process_monitor.param.yaml (100%) rename {system_launch/config => autoware_launch/config/system}/system_monitor/voltage_monitor.param.yaml (100%) create mode 100644 autoware_launch/launch/components/tier4_system_component.launch.xml rename {system_launch => autoware_launch}/system_launch.drawio.svg (100%) delete mode 100644 system_launch/CMakeLists.txt delete mode 100644 system_launch/README.md delete mode 100644 system_launch/config/system_error_monitor.param.yaml delete mode 100644 system_launch/launch/dummy_diag_publisher/control.launch.xml delete mode 100644 system_launch/launch/dummy_diag_publisher/localization.launch.xml delete mode 100644 system_launch/launch/dummy_diag_publisher/system.launch.xml delete mode 100644 system_launch/launch/dummy_diag_publisher/vehicle.launch.xml delete mode 100644 system_launch/launch/system.launch.xml delete mode 100644 system_launch/package.xml diff --git a/system_launch/config/component_state_monitor/topics.yaml b/autoware_launch/config/system/component_state_monitor/topics.yaml similarity index 100% rename from system_launch/config/component_state_monitor/topics.yaml rename to autoware_launch/config/system/component_state_monitor/topics.yaml diff --git a/system_launch/config/diagnostic_aggregator/system.param.yaml b/autoware_launch/config/system/diagnostic_aggregator/system.param.yaml similarity index 100% rename from system_launch/config/diagnostic_aggregator/system.param.yaml rename to autoware_launch/config/system/diagnostic_aggregator/system.param.yaml diff --git a/system_launch/config/diagnostic_aggregator/vehicle.param.yaml b/autoware_launch/config/system/diagnostic_aggregator/vehicle.param.yaml similarity index 100% rename from system_launch/config/diagnostic_aggregator/vehicle.param.yaml rename to autoware_launch/config/system/diagnostic_aggregator/vehicle.param.yaml diff --git a/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml b/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml new file mode 100644 index 0000000000..480615d762 --- /dev/null +++ b/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml @@ -0,0 +1,49 @@ +# Description: +# required_diags: +# : {is_active: , status: } +# name: diag name +# is_active: Force update or not +# status: diag status set by dummy diag publisher "OK, Warn, Error, Stale" +# +# Note: +# +# default values are: +# is_active: "true" +# status: "OK" +--- +/**: + ros__parameters: + required_diags: + + # control + joy_controller_connection: default + + # locallization + localization_accuracy: default + ndt_scan_matcher: default + + # system + bagpacker: default + NTP Offset: default + CPU Temperature: default + CPU Usage: default + CPU Thermal Throttling: default + CPU Frequency: default + CPU Load Average: default + GPU Temperature: default + GPU Usage: default + GPU Memory Usage: default + GPU Thermal Throttling: default + Memory Usage: default + Network Usage: default + Network Traffic: default + HDD Temperature: default + HDD Usage: default + HDD PowerOnHours: default + HDD TotalDataWritten: default + High-load: default + High-mem: default + Tasks Summary: default + + #vehicle + vehicle_errors: default diff --git a/system_launch/config/emergency_handler/emergency_handler.param.yaml b/autoware_launch/config/system/emergency_handler/emergency_handler.param.yaml similarity index 100% rename from system_launch/config/emergency_handler/emergency_handler.param.yaml rename to autoware_launch/config/system/emergency_handler/emergency_handler.param.yaml diff --git a/system_launch/config/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator.param.yaml b/autoware_launch/config/system/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator.param.yaml similarity index 100% rename from system_launch/config/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator.param.yaml rename to autoware_launch/config/system/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator.param.yaml diff --git a/system_launch/config/mrm_emergency_stop_operator/mrm_emergency_stop_operator.param.yaml b/autoware_launch/config/system/mrm_emergency_stop_operator/mrm_emergency_stop_operator.param.yaml similarity index 100% rename from system_launch/config/mrm_emergency_stop_operator/mrm_emergency_stop_operator.param.yaml rename to autoware_launch/config/system/mrm_emergency_stop_operator/mrm_emergency_stop_operator.param.yaml diff --git a/system_launch/config/system_error_monitor/system_error_monitor.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml similarity index 100% rename from system_launch/config/system_error_monitor/system_error_monitor.param.yaml rename to autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml diff --git a/system_launch/config/system_error_monitor/system_error_monitor.planning_simulation.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml similarity index 100% rename from system_launch/config/system_error_monitor/system_error_monitor.planning_simulation.param.yaml rename to autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml diff --git a/system_launch/config/system_monitor/cpu_monitor.param.yaml b/autoware_launch/config/system/system_monitor/cpu_monitor.param.yaml similarity index 100% rename from system_launch/config/system_monitor/cpu_monitor.param.yaml rename to autoware_launch/config/system/system_monitor/cpu_monitor.param.yaml diff --git a/system_launch/config/system_monitor/gpu_monitor.param.yaml b/autoware_launch/config/system/system_monitor/gpu_monitor.param.yaml similarity index 100% rename from system_launch/config/system_monitor/gpu_monitor.param.yaml rename to autoware_launch/config/system/system_monitor/gpu_monitor.param.yaml diff --git a/system_launch/config/system_monitor/hdd_monitor.param.yaml b/autoware_launch/config/system/system_monitor/hdd_monitor.param.yaml similarity index 100% rename from system_launch/config/system_monitor/hdd_monitor.param.yaml rename to autoware_launch/config/system/system_monitor/hdd_monitor.param.yaml diff --git a/system_launch/config/system_monitor/mem_monitor.param.yaml b/autoware_launch/config/system/system_monitor/mem_monitor.param.yaml similarity index 100% rename from system_launch/config/system_monitor/mem_monitor.param.yaml rename to autoware_launch/config/system/system_monitor/mem_monitor.param.yaml diff --git a/system_launch/config/system_monitor/net_monitor.param.yaml b/autoware_launch/config/system/system_monitor/net_monitor.param.yaml similarity index 100% rename from system_launch/config/system_monitor/net_monitor.param.yaml rename to autoware_launch/config/system/system_monitor/net_monitor.param.yaml diff --git a/system_launch/config/system_monitor/ntp_monitor.param.yaml b/autoware_launch/config/system/system_monitor/ntp_monitor.param.yaml similarity index 100% rename from system_launch/config/system_monitor/ntp_monitor.param.yaml rename to autoware_launch/config/system/system_monitor/ntp_monitor.param.yaml diff --git a/system_launch/config/system_monitor/process_monitor.param.yaml b/autoware_launch/config/system/system_monitor/process_monitor.param.yaml similarity index 100% rename from system_launch/config/system_monitor/process_monitor.param.yaml rename to autoware_launch/config/system/system_monitor/process_monitor.param.yaml diff --git a/system_launch/config/system_monitor/voltage_monitor.param.yaml b/autoware_launch/config/system/system_monitor/voltage_monitor.param.yaml similarity index 100% rename from system_launch/config/system_monitor/voltage_monitor.param.yaml rename to autoware_launch/config/system/system_monitor/voltage_monitor.param.yaml diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 45155cfe86..a1662d0de5 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -65,7 +65,7 @@ - + diff --git a/autoware_launch/launch/components/tier4_system_component.launch.xml b/autoware_launch/launch/components/tier4_system_component.launch.xml new file mode 100644 index 0000000000..214b10ea0a --- /dev/null +++ b/autoware_launch/launch/components/tier4_system_component.launch.xml @@ -0,0 +1,29 @@ + + + + + + + + . + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 4cc04cc4f4..94d27c5e29 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -6,16 +6,20 @@ Yukihiro Saito Takagi, Isamu + Akihiro Sakurai Apache License 2.0 ament_cmake_auto ad_api_adaptors + component_state_monitor + emergency_handler global_parameter_loader python3-bson python3-tornado + system_error_monitor + system_monitor rviz2 - system_launch tier4_autoware_api_launch tier4_control_launch tier4_localization_launch @@ -24,6 +28,7 @@ tier4_planning_launch tier4_sensing_launch tier4_simulator_launch + tier4_system_launch tier4_vehicle_launch ament_lint_auto diff --git a/system_launch/system_launch.drawio.svg b/autoware_launch/system_launch.drawio.svg similarity index 100% rename from system_launch/system_launch.drawio.svg rename to autoware_launch/system_launch.drawio.svg diff --git a/system_launch/CMakeLists.txt b/system_launch/CMakeLists.txt deleted file mode 100644 index 656e60c6d0..0000000000 --- a/system_launch/CMakeLists.txt +++ /dev/null @@ -1,20 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(system_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() - -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/system_launch/README.md b/system_launch/README.md deleted file mode 100644 index 793c045fc9..0000000000 --- a/system_launch/README.md +++ /dev/null @@ -1,17 +0,0 @@ -# system_launch - -## Structure - -![system_launch](./system_launch.drawio.svg) - -## Package Dependencies - -Please see `` in `package.xml`. - -## Usage - -```xml - - - -``` diff --git a/system_launch/config/system_error_monitor.param.yaml b/system_launch/config/system_error_monitor.param.yaml deleted file mode 100644 index 71dc2ac600..0000000000 --- a/system_launch/config/system_error_monitor.param.yaml +++ /dev/null @@ -1,52 +0,0 @@ -# Description: -# name: diag name -# sf_at: diag level where it becomes Safe Fault -# lf_at: diag level where it becomes Latent Fault -# spf_at: diag level where it becomes Single Point Fault -# auto_recovery: Determines whether the system will automatically recover when it recovers from an error. -# -# Note: -# empty-value for sf_at, lf_at and spf_at is "none" -# default values are: -# sf_at: "none" -# lf_at: "warn" -# spf_at: "error" -# auto_recovery: "true" ---- -/**: - ros__parameters: - required_modules: - autonomous_driving: - /autoware/control/autonomous_driving/node_alive_monitoring: default - /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default - /autoware/control/control_command_gate/node_alive_monitoring: default - - /autoware/localization/node_alive_monitoring: default - /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } - /autoware/localization/performance_monitoring/localization_accuracy: default - - /autoware/map/node_alive_monitoring: default - - /autoware/perception/node_alive_monitoring: default - - /autoware/planning/node_alive_monitoring: default - /autoware/planning/performance_monitoring/trajectory_validation: default - - # /autoware/sensing/node_alive_monitoring: default - - /autoware/system/node_alive_monitoring: default - /autoware/system/emergency_stop_operation: default - /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } - /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "none", spf_at: "none" } - - /autoware/vehicle/node_alive_monitoring: default - - external_control: - /autoware/control/control_command_gate/node_alive_monitoring: default - /autoware/control/external_control/external_command_selector/node_alive_monitoring: default - - /autoware/system/node_alive_monitoring: default - /autoware/system/emergency_stop_operation: default - /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } - - /autoware/vehicle/node_alive_monitoring: default diff --git a/system_launch/launch/dummy_diag_publisher/control.launch.xml b/system_launch/launch/dummy_diag_publisher/control.launch.xml deleted file mode 100644 index b93a93d927..0000000000 --- a/system_launch/launch/dummy_diag_publisher/control.launch.xml +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/system_launch/launch/dummy_diag_publisher/localization.launch.xml b/system_launch/launch/dummy_diag_publisher/localization.launch.xml deleted file mode 100644 index 19f70a723d..0000000000 --- a/system_launch/launch/dummy_diag_publisher/localization.launch.xml +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/system_launch/launch/dummy_diag_publisher/system.launch.xml b/system_launch/launch/dummy_diag_publisher/system.launch.xml deleted file mode 100644 index e56227a7a4..0000000000 --- a/system_launch/launch/dummy_diag_publisher/system.launch.xml +++ /dev/null @@ -1,87 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/system_launch/launch/dummy_diag_publisher/vehicle.launch.xml b/system_launch/launch/dummy_diag_publisher/vehicle.launch.xml deleted file mode 100644 index 3848c9e7e9..0000000000 --- a/system_launch/launch/dummy_diag_publisher/vehicle.launch.xml +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml deleted file mode 100644 index 7360aadb0a..0000000000 --- a/system_launch/launch/system.launch.xml +++ /dev/null @@ -1,84 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/system_launch/package.xml b/system_launch/package.xml deleted file mode 100644 index 9d3e90ad2d..0000000000 --- a/system_launch/package.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - system_launch - 0.1.0 - The system_launch package - - Kenji Miyake - Apache License 2.0 - - ament_cmake_auto - - component_state_monitor - emergency_handler - system_error_monitor - system_monitor - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - From 0aa01a50447c7f050321fd59fd00175ba6030caa Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 6 Feb 2023 10:53:13 +0900 Subject: [PATCH 778/851] chore(autoware_launch): manual sync with awf/autoware_launch (#751) * manual sync with awf/autoware_launch Signed-off-by: kminoda * ci(pre-commit): autofix * add map launch Signed-off-by: kminoda --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/localization/ndt_scan_matcher.param.yaml | 11 +++++++++++ .../config/map/pointcloud_map_loader.param.yaml | 4 ++-- 2 files changed, 13 insertions(+), 2 deletions(-) diff --git a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml index e38f75a3f8..5070aa2868 100644 --- a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml +++ b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml @@ -1,5 +1,7 @@ /**: ros__parameters: + # Use dynamic map loading + use_dynamic_map_loading: true # Vehicle reference frame base_frame: "base_link" @@ -64,3 +66,12 @@ # Regularization scale factor regularization_scale_factor: 0.01 + + # Radius of input LiDAR range (used for diagnostics of dynamic map loading) + lidar_radius: 100.0 + + # A flag for using scan matching score based on de-grounded LiDAR scan + estimate_scores_for_degrounded_scan: false + + # If lidar_point.z - base_link.z <= this threshold , the point will be removed + z_margin_for_ground_removal: 0.8 diff --git a/autoware_launch/config/map/pointcloud_map_loader.param.yaml b/autoware_launch/config/map/pointcloud_map_loader.param.yaml index 8f3ccbff00..61b02c490c 100644 --- a/autoware_launch/config/map/pointcloud_map_loader.param.yaml +++ b/autoware_launch/config/map/pointcloud_map_loader.param.yaml @@ -2,8 +2,8 @@ ros__parameters: enable_whole_load: true enable_downsampled_whole_load: false - enable_partial_load: false - enable_differential_load: false + enable_partial_load: true + enable_differential_load: true # only used when downsample_whole_load enabled leaf_size: 3.0 # downsample leaf size [m] From d651a831cdb98e5789207af5b7951bbb1813053f Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 6 Feb 2023 11:21:12 +0900 Subject: [PATCH 779/851] chore(autoware_launch): change lane_change_sampling_num from 10 to 3 (#742) Signed-off-by: tomoya.kimura --- .../behavior_path_planner/lane_change/lane_change.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml index c25eb73d62..af8009a416 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -14,7 +14,7 @@ minimum_lane_change_velocity: 2.78 # [m/s] prediction_time_resolution: 0.5 # [s] maximum_deceleration: 1.0 # [m/s2] - lane_change_sampling_num: 10 + lane_change_sampling_num: 3 # collision check enable_collision_check_at_prepare_phase: false From 8c6ae27ed7eed0cfceb542d38de21071b2c3cc60 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 6 Feb 2023 11:45:55 +0900 Subject: [PATCH 780/851] chore(autoware_launch): minor parameter change for control (#749) Signed-off-by: Takayuki Murooka --- .../trajectory_follower/lateral/mpc.param.yaml | 12 ------------ 1 file changed, 12 deletions(-) diff --git a/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml index 2324976f49..400bc926a1 100644 --- a/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml +++ b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml @@ -70,15 +70,3 @@ update_steer_threshold: 0.035 average_num: 1000 steering_offset_limit: 0.02 - - # vehicle parameters - vehicle: - cg_to_front_m: 1.228 - cg_to_rear_m: 1.5618 - mass_kg: 2400.0 - mass_fl: 600.0 - mass_fr: 600.0 - mass_rl: 600.0 - mass_rr: 600.0 - cf: 155494.663 - cr: 155494.663 From a6ef5b2b812b07d898aac1976c227b0886768e5f Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 6 Feb 2023 14:43:58 +0900 Subject: [PATCH 781/851] feat(planning_config): update params to enable 60kmph speed (#744) Signed-off-by: Takamasa Horibe --- .../planning/scenario_planning/common/common.param.yaml | 4 ++-- .../motion_velocity_smoother.param.yaml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml index a23570a5fc..6bb130e805 100644 --- a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml @@ -2,9 +2,9 @@ ros__parameters: # constraints param for normal driving normal: - min_acc: -0.5 # min deceleration [m/ss] + min_acc: -1.0 # min deceleration [m/ss] max_acc: 1.0 # max acceleration [m/ss] - min_jerk: -0.5 # min jerk [m/sss] + min_jerk: -1.0 # min jerk [m/sss] max_jerk: 1.0 # max jerk [m/sss] # constraints to be observed diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index 9534a87fc5..e600334ee2 100644 --- a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -32,7 +32,7 @@ # resampling parameters for optimization max_trajectory_length: 200.0 # max trajectory length for resampling [m] - min_trajectory_length: 150.0 # min trajectory length for resampling [m] + min_trajectory_length: 180.0 # min trajectory length for resampling [m] resample_time: 2.0 # resample total time for dense sampling [s] dense_resample_dt: 0.2 # resample time interval for dense sampling [s] dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m] From 43b729c5b0b18c7b39302e57594bd0d2238ece68 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 6 Feb 2023 18:49:43 +0900 Subject: [PATCH 782/851] feat: add behavior tree file with external lane change request (#756) Signed-off-by: tomoya.kimura --- ..._planner_tree_with_external_request_LC.xml | 74 +++++++++++++++++++ 1 file changed, 74 insertions(+) create mode 100644 autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree_with_external_request_LC.xml diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree_with_external_request_LC.xml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree_with_external_request_LC.xml new file mode 100644 index 0000000000..e848f156a4 --- /dev/null +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner_tree_with_external_request_LC.xml @@ -0,0 +1,74 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + desc + + + + + desc + + + + desc + + + + desc + + + + desc + + + + + + + + desc + + + + desc + + + + + From 36123bf252ece9ba2931c3c83407f9e822325dd6 Mon Sep 17 00:00:00 2001 From: asana17 Date: Mon, 6 Feb 2023 21:52:19 +0900 Subject: [PATCH 783/851] modify file name --- .../launch/components/tier4_system_component.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/launch/components/tier4_system_component.launch.xml b/autoware_launch/launch/components/tier4_system_component.launch.xml index 214b10ea0a..a7ce52d3cf 100644 --- a/autoware_launch/launch/components/tier4_system_component.launch.xml +++ b/autoware_launch/launch/components/tier4_system_component.launch.xml @@ -13,7 +13,7 @@ - + From 513d0388913cb7627445d31a95eff6f13e797490 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 6 Feb 2023 22:56:47 +0900 Subject: [PATCH 784/851] fix(multi_object_tracker): update data association matrix (#755) * fix(multi_object_tracker): update data association matrix Signed-off-by: Muhammad Zulfaqar Azmi * updated parameter Signed-off-by: Muhammad Zulfaqar Azmi * Update autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml also update for CAR->other objects Co-authored-by: Yukihiro Saito --------- Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: Yukihiro Saito --- .../data_association_matrix.param.yaml | 26 +++++++++---------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml index 2541ab0367..69af202e7a 100644 --- a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml +++ b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml @@ -14,10 +14,10 @@ max_dist_matrix: #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN [4.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN - 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR - 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK - 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS - 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER + 4.0, 2.5, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR + 4.0, 2.5, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK + 4.0, 2.5, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS + 4.0, 2.5, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #MOTORBIKE 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #BICYCLE 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN @@ -55,12 +55,12 @@ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN min_iou_matrix: # If value is negative, it will be ignored. - #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN - [0.0001, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN - 0.1, 0.1, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR - 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK - 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS - 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER - 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE - 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE - 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.0001] #PEDESTRIAN + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [0.0001, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN + 0.1, 0.1, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER + 0.1, 0.1, 0.1, 0.1, 0.1, -1.0, 0.1, 0.1, #MOTORBIKE + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.0001] #PEDESTRIAN From 4b3ff2257b96d816da9c826de1f85428dc096f65 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 7 Feb 2023 01:13:02 +0900 Subject: [PATCH 785/851] fix(autoware_launch): change behavior_velocity parameters (#716) Signed-off-by: Takayuki Murooka --- .../occlusion_spot.param.yaml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml index 957f7988a6..0b93ea5308 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml @@ -4,7 +4,7 @@ detection_method: "occupancy_grid" # [-] candidate is "occupancy_grid" or "predicted_object" pass_judge: "smooth_velocity" # [-] candidate is "smooth_velocity" or "current_velocity" use_object_info: true # [-] whether to reflect object info to occupancy grid map or not - use_moving_object_ray_cast: true # [-] whether to reflect moving object ray_cast to occupancy grid map or not + use_moving_object_ray_cast: true # [-] whether to reflect moving object ray shadow grid map use_partition_lanelet: true # [-] whether to use partition lanelet map data pedestrian_vel: 1.5 # [m/s] assume pedestrian is dashing from occlusion at this velocity pedestrian_radius: 0.3 # [m] assume pedestrian width(0.2m) + margin(0.1m) @@ -18,8 +18,8 @@ lateral_distance: 1.5 # [m] maximum lateral distance to consider hidden collision motion: safety_ratio: 0.8 # [-] jerk/acceleration ratio for safety - max_slow_down_jerk: -0.5 # [m/s^3] minimum jerk deceleration for safe brake. - max_slow_down_accel: -1.8 # [m/s^2] minimum accel deceleration for safe brake. + max_slow_down_jerk: -0.3 # [m/s^3] minimum jerk deceleration for safe brake. + max_slow_down_accel: -1.5 # [m/s^2] minimum accel deceleration for safe brake. non_effective_jerk: -0.3 # [m/s^3] weak jerk for velocity planning. non_effective_acceleration: -1.0 # [m/s^2] weak deceleration for velocity planning. min_allowed_velocity: 1.0 # [m/s] minimum velocity allowed @@ -28,7 +28,7 @@ min_occlusion_spot_size: 1.0 # [m] occupancy grid must contain an UNKNOWN area of at least size NxN to be considered a hidden obstacle. slice_length: 10.0 # [m] size of slices in both length and distance relative to the ego path. min_longitudinal_offset: 1.0 # [m] detection area safety buffer from front bumper. - max_lateral_distance: 6.0 # [m] buffer around the ego path used to build the detection area. + max_lateral_distance: 5.0 # [m] buffer around the ego path used to build the detection area. grid: free_space_max: 43 # [-] maximum value of a free space cell in the occupancy grid - occupied_min: 58 # [-] minimum value of an occupied cell in the occupancy grid + occupied_min: 57 # [-] minimum value of an occupied cell in the occupancy grid From 2ab3dd1c6b90b7ee34ad0f51b60e5e9cf4685911 Mon Sep 17 00:00:00 2001 From: asana17 Date: Tue, 7 Feb 2023 10:24:05 +0900 Subject: [PATCH 786/851] modified launch_system_monitor param modified launch_system_monitor param modified launch_system_monitor_param --- autoware_launch/launch/autoware.launch.xml | 2 ++ .../launch/components/tier4_system_component.launch.xml | 2 ++ autoware_launch/launch/planning_simulator.launch.xml | 3 +++ 3 files changed, 7 insertions(+) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index a1662d0de5..98540feaa1 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -29,6 +29,7 @@ + @@ -67,6 +68,7 @@ + diff --git a/autoware_launch/launch/components/tier4_system_component.launch.xml b/autoware_launch/launch/components/tier4_system_component.launch.xml index a7ce52d3cf..d2381a6be6 100644 --- a/autoware_launch/launch/components/tier4_system_component.launch.xml +++ b/autoware_launch/launch/components/tier4_system_component.launch.xml @@ -2,11 +2,13 @@ + . + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 62fc034a6e..388b0952b2 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -9,6 +9,8 @@ + + @@ -41,6 +43,7 @@ + From 22fe720a3d868a0959ec5926433817e5d282673e Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 7 Feb 2023 07:33:59 +0000 Subject: [PATCH 787/851] ci(pre-commit): autofix --- .../system/dummy_diag_publisher/dummy_diag_publisher.param.yaml | 2 +- autoware_launch/package.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml b/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml index 480615d762..5f975fafd7 100644 --- a/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml +++ b/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml @@ -14,7 +14,7 @@ /**: ros__parameters: required_diags: - + # control joy_controller_connection: default diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 94d27c5e29..d3f305192f 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -17,9 +17,9 @@ global_parameter_loader python3-bson python3-tornado + rviz2 system_error_monitor system_monitor - rviz2 tier4_autoware_api_launch tier4_control_launch tier4_localization_launch From 1a89cb82e5379039b8c767b194cdbf0dbcea2280 Mon Sep 17 00:00:00 2001 From: asana17 Date: Tue, 7 Feb 2023 16:55:31 +0900 Subject: [PATCH 788/851] fix typo --- .../system/dummy_diag_publisher/dummy_diag_publisher.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml b/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml index 5f975fafd7..198aa0cfab 100644 --- a/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml +++ b/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml @@ -18,7 +18,7 @@ # control joy_controller_connection: default - # locallization + # localization localization_accuracy: default ndt_scan_matcher: default From fc88cb37800f796e856dbcc9ef690a165e708382 Mon Sep 17 00:00:00 2001 From: asana17 Date: Tue, 7 Feb 2023 17:04:45 +0900 Subject: [PATCH 789/851] modified package.xml --- autoware_launch/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index d3f305192f..1974c80d21 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -13,6 +13,7 @@ ad_api_adaptors component_state_monitor + dummy_diag_publisher emergency_handler global_parameter_loader python3-bson From 2a3bdbb2fa51fb2da621e89f10f4fb539deb0e51 Mon Sep 17 00:00:00 2001 From: asana17 Date: Wed, 8 Feb 2023 14:38:02 +0900 Subject: [PATCH 790/851] Signed-off-by: asana17 removed unnecessary dependencies --- autoware_launch/package.xml | 5 ----- 1 file changed, 5 deletions(-) diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 1974c80d21..08c5b12a8f 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -12,15 +12,10 @@ ament_cmake_auto ad_api_adaptors - component_state_monitor - dummy_diag_publisher - emergency_handler global_parameter_loader python3-bson python3-tornado rviz2 - system_error_monitor - system_monitor tier4_autoware_api_launch tier4_control_launch tier4_localization_launch From 04d0ad5a17b790cdfd4e6f2cd87b5778be633e25 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 9 Feb 2023 10:19:21 +0900 Subject: [PATCH 791/851] feat(autoware_launch): add option to disable path update during avoidance (#763) Signed-off-by: Takayuki Murooka --- .../behavior_path_planner/avoidance/avoidance.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index 40de19bd6c..77e14f70f8 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -17,6 +17,7 @@ enable_update_path_when_object_is_gone: false enable_safety_check: false enable_yield_maneuver: false + disable_path_update: false # for debug publish_debug_marker: false From cc9fdbb19bec52cd9bd6dd8a0336f1304ab7139d Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 13 Feb 2023 14:56:59 +0900 Subject: [PATCH 792/851] fix(behavior_velocity_planner): continue collision checking after pass judge (#769) fix(behavior_velocity_planner): revert part of #2719 Signed-off-by: Mamoru Sobue --- .../behavior_velocity_planner/intersection.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index 9ed153bb1c..c46861d32a 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -3,6 +3,7 @@ intersection: state_transit_margin_time: 1.0 stop_line_margin: 3.0 + keep_detection_vel_thr: 0.833 # == 3.0km/h. keep detection if ego is ego.vel < keep_detection_vel_thr stuck_vehicle_detect_dist: 3.0 # this should be the length between cars when they are stopped. The actual stuck vehicle detection length will be this value + vehicle_length. stuck_vehicle_ignore_dist: 10.0 # obstacle stop max distance(5.0m) + stuck vehicle size / 2 (0.0m-) stuck_vehicle_vel_thr: 0.833 # 0.833m/s = 3.0km/h From 10663f3a0b041f9409c1550fb795c13c72071ea9 Mon Sep 17 00:00:00 2001 From: asana17 Date: Thu, 16 Feb 2023 14:17:58 +0900 Subject: [PATCH 793/851] add launch_dummy_diag_publisher param Signed-off-by: asana17 --- autoware_launch/launch/autoware.launch.xml | 2 ++ .../launch/components/tier4_system_component.launch.xml | 2 ++ autoware_launch/launch/e2e_simulator.launch.xml | 2 ++ autoware_launch/launch/planning_simulator.launch.xml | 2 ++ 4 files changed, 8 insertions(+) diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 98540feaa1..46413a95f2 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -30,6 +30,7 @@ + @@ -69,6 +70,7 @@ + diff --git a/autoware_launch/launch/components/tier4_system_component.launch.xml b/autoware_launch/launch/components/tier4_system_component.launch.xml index d2381a6be6..94db9bf58c 100644 --- a/autoware_launch/launch/components/tier4_system_component.launch.xml +++ b/autoware_launch/launch/components/tier4_system_component.launch.xml @@ -3,12 +3,14 @@ + . + diff --git a/autoware_launch/launch/e2e_simulator.launch.xml b/autoware_launch/launch/e2e_simulator.launch.xml index 317decda57..2ebf8bb50b 100644 --- a/autoware_launch/launch/e2e_simulator.launch.xml +++ b/autoware_launch/launch/e2e_simulator.launch.xml @@ -24,6 +24,7 @@ + @@ -53,6 +54,7 @@ + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 388b0952b2..5a5dd5981b 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -11,6 +11,7 @@ + @@ -44,6 +45,7 @@ + From 370ec9a5fdc8e47293c6432bacf0ef7db6fead3b Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 17 Feb 2023 01:41:05 +0900 Subject: [PATCH 794/851] fix(autoware_launch): unify with awf launch (#781) * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * apply awf's system parameters Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * copy all minor files from awf Signed-off-by: Takayuki Murooka * revert minor files Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .pre-commit-config.yaml | 5 +- README.md | 24 +- .../localization/ndt_scan_matcher.param.yaml | 1 + .../lane_change/lane_change.param.yaml | 1 + .../rtc_auto_mode_manager.param.yaml | 2 - .../obstacle_avoidance_planner.param.yaml | 3 + .../diagnostic_aggregator/system.param.yaml | 15 - .../emergency_handler.param.yaml | 2 + .../diagnostic_aggregator/vehicle.param.yaml | 0 .../system_error_monitor.param.yaml | 4 +- ...ror_monitor.planning_simulation.param.yaml | 9 +- .../system_monitor/net_monitor.param.yaml | 14 +- autoware_launch/launch/autoware.launch.xml | 6 +- .../tier4_localization_component.launch.xml | 3 +- .../tier4_system_component.launch.xml | 7 +- autoware_launch/package.xml | 2 - autoware_launch/rviz/autoware.rviz | 171 +++------- autoware_launch/system_launch.drawio.svg | 308 ------------------ build_depends.repos | 4 +- 19 files changed, 88 insertions(+), 493 deletions(-) delete mode 100644 autoware_launch/config/system/diagnostic_aggregator/system.param.yaml rename autoware_launch/config/system/{ => system_error_monitor}/diagnostic_aggregator/vehicle.param.yaml (100%) delete mode 100644 autoware_launch/system_launch.drawio.svg diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 4b9105a923..2aa48be7ab 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -1,5 +1,5 @@ ci: - autofix_commit_msg: "ci(pre-commit): autofix" + autofix_commit_msg: "style(pre-commit): autofix" autoupdate_commit_msg: "ci(pre-commit): autoupdate" repos: @@ -37,7 +37,10 @@ repos: rev: v0.8.0 hooks: - id: flake8-ros + - id: prettier-xacro + - id: prettier-launch-xml - id: prettier-package-xml + - id: ros-include-guard - id: sort-package-xml - repo: https://github.com/shellcheck-py/shellcheck-py diff --git a/README.md b/README.md index dc6f607866..45153ea612 100644 --- a/README.md +++ b/README.md @@ -1,23 +1,3 @@ -# autoware_launcher +# autoware_launch -## Getting started - -### Using real vehicle - -```bash -ros2 launch autoware_launch autoware.launch.xml map_path:=/path/to/map_folder vehicle_model:=[vehicle_name] sensor_model:=[sensor_name] -``` - -### Using planning simulator - -```bash -ros2 launch autoware_launch planning_simulator.launch.xml map_path:=/path/to/map_folder vehicle_model:=[vehicle_name] sensor_model:=[sensor_name] -``` - -## Directory structure - -- [autoware_launch](./autoware_launch) -- [control_launch](./control_launch) -- [integration_launch](./integration_launch) -- [planning_launch](./planning_launch) -- [system_launch](./system_launch) +A launch configuration repository for [Autoware](https://github.com/autowarefoundation/autoware), containing node configurations and their parameters. diff --git a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml index 365b42c47a..4c29059581 100644 --- a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml +++ b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml @@ -51,6 +51,7 @@ num_threads: 4 # The covariance of output pose + # Do note that this covariance matrix is empirically derived output_pose_covariance: [ 0.0225, 0.0, 0.0, 0.0, 0.0, 0.0, diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml index af8009a416..295769acb3 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -2,6 +2,7 @@ ros__parameters: lane_change: lane_change_prepare_duration: 4.0 # [s] + lane_changing_safety_check_duration: 8.0 # [s] minimum_lane_change_prepare_distance: 2.0 # [m] minimum_lane_change_length: 16.5 # [m] diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml index 0e3391e69e..8ba0a402ee 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml @@ -7,8 +7,6 @@ - "intersection" - "no_stopping_area" - "traffic_light" - - "ext_request_lane_change_left" - - "ext_request_lane_change_right" - "lane_change_left" - "lane_change_right" - "avoidance_left" diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index a6d035830c..c2aab909e8 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -152,6 +152,9 @@ num: 3 radius_ratio: 0.8 + fitting_uniform_circle: + num: 3 # must be greater than 1 + rear_drive: num_for_calculation: 3 front_radius_ratio: 1.0 diff --git a/autoware_launch/config/system/diagnostic_aggregator/system.param.yaml b/autoware_launch/config/system/diagnostic_aggregator/system.param.yaml deleted file mode 100644 index 27cbe3fed2..0000000000 --- a/autoware_launch/config/system/diagnostic_aggregator/system.param.yaml +++ /dev/null @@ -1,15 +0,0 @@ -/**: - ros__parameters: - system: - type: diagnostic_aggregator/AnalyzerGroup - path: system - analyzers: - debug_data_logger: - type: diagnostic_aggregator/AnalyzerGroup - path: debug_data_logger - analyzers: - storage_error: - type: diagnostic_aggregator/GenericAnalyzer - path: storage_error - contains: ["bagpacker"] - timeout: 3.0 diff --git a/autoware_launch/config/system/emergency_handler/emergency_handler.param.yaml b/autoware_launch/config/system/emergency_handler/emergency_handler.param.yaml index 76ea50719a..652a984ce5 100644 --- a/autoware_launch/config/system/emergency_handler/emergency_handler.param.yaml +++ b/autoware_launch/config/system/emergency_handler/emergency_handler.param.yaml @@ -1,3 +1,5 @@ +# Default configuration for emergency handler +--- /**: ros__parameters: update_rate: 10 diff --git a/autoware_launch/config/system/diagnostic_aggregator/vehicle.param.yaml b/autoware_launch/config/system/system_error_monitor/diagnostic_aggregator/vehicle.param.yaml similarity index 100% rename from autoware_launch/config/system/diagnostic_aggregator/vehicle.param.yaml rename to autoware_launch/config/system/system_error_monitor/diagnostic_aggregator/vehicle.param.yaml diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml index b9a5a4fa79..71dc2ac600 100644 --- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml +++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml @@ -32,10 +32,11 @@ /autoware/planning/node_alive_monitoring: default /autoware/planning/performance_monitoring/trajectory_validation: default - /autoware/sensing/node_alive_monitoring: default + # /autoware/sensing/node_alive_monitoring: default /autoware/system/node_alive_monitoring: default /autoware/system/emergency_stop_operation: default + /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "none", spf_at: "none" } /autoware/vehicle/node_alive_monitoring: default @@ -46,5 +47,6 @@ /autoware/system/node_alive_monitoring: default /autoware/system/emergency_stop_operation: default + /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } /autoware/vehicle/node_alive_monitoring: default diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml index 27fd3c1e4d..9708456df4 100644 --- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml +++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml @@ -1,3 +1,4 @@ +# Description: # name: diag name # sf_at: diag level where it becomes Safe Fault # lf_at: diag level where it becomes Latent Fault @@ -21,8 +22,8 @@ /autoware/control/control_command_gate/node_alive_monitoring: default /autoware/localization/node_alive_monitoring: default - /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } - /autoware/localization/performance_monitoring/localization_accuracy: default + # /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } + # /autoware/localization/performance_monitoring/localization_accuracy: default /autoware/map/node_alive_monitoring: default @@ -35,7 +36,8 @@ /autoware/system/node_alive_monitoring: default /autoware/system/emergency_stop_operation: default - /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "none", spf_at: "none" } + /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } + # /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "error", spf_at: "none" } /autoware/vehicle/node_alive_monitoring: default @@ -45,5 +47,6 @@ /autoware/system/node_alive_monitoring: default /autoware/system/emergency_stop_operation: default + /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } /autoware/vehicle/node_alive_monitoring: default diff --git a/autoware_launch/config/system/system_monitor/net_monitor.param.yaml b/autoware_launch/config/system/system_monitor/net_monitor.param.yaml index cb7e1b4838..d72b8d1334 100644 --- a/autoware_launch/config/system/system_monitor/net_monitor.param.yaml +++ b/autoware_launch/config/system/system_monitor/net_monitor.param.yaml @@ -1,9 +1,9 @@ /**: ros__parameters: - devices: ["*"] - traffic_reader_port: 7636 - monitor_program: "greengrass" - crc_error_check_duration: 1 - crc_error_count_threshold: 1 - reassembles_failed_check_duration: 1 - reassembles_failed_check_count: 1 + devices: ["*"] + traffic_reader_port: 7636 + monitor_program: "greengrass" + crc_error_check_duration: 1 + crc_error_count_threshold: 1 + reassembles_failed_check_duration: 1 + reassembles_failed_check_count: 1 diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index b24d3344fd..e3d9755f15 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -104,8 +104,8 @@ - - - + + + diff --git a/autoware_launch/launch/components/tier4_localization_component.launch.xml b/autoware_launch/launch/components/tier4_localization_component.launch.xml index 7ef5fa06fc..242ec17642 100644 --- a/autoware_launch/launch/components/tier4_localization_component.launch.xml +++ b/autoware_launch/launch/components/tier4_localization_component.launch.xml @@ -1,7 +1,8 @@ - + + diff --git a/autoware_launch/launch/components/tier4_system_component.launch.xml b/autoware_launch/launch/components/tier4_system_component.launch.xml index 84ac5197a5..d73d5b3b5a 100644 --- a/autoware_launch/launch/components/tier4_system_component.launch.xml +++ b/autoware_launch/launch/components/tier4_system_component.launch.xml @@ -1,12 +1,10 @@ - + - - @@ -14,8 +12,7 @@ - - + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 08c5b12a8f..eb83f2597c 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -5,8 +5,6 @@ The autoware_launch package Yukihiro Saito - Takagi, Isamu - Akihiro Sakurai Apache License 2.0 ament_cmake_auto diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 4fe3b9cd80..fbfe61ad3c 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -365,6 +365,7 @@ Visualization Manager: pedestrian_marking: true right_lane_bound: true road_lanelets: false + speed_bump: true stop_lines: true shoulder_center_lane_line: false shoulder_left_lane_bound: true @@ -1036,36 +1037,13 @@ Visualization Manager: - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true - Name: PathChangeCandidate_ExternalRequestLaneChangeRight - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/ext_request_lane_change_right - Value: true - View Path: - Alpha: 0.30000001192092896 - Color: 115; 210; 22 - Constant Color: false - Value: true - Width: 2 - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_ExternalRequestLaneChangeLeft + Name: PathChangeCandidate_Avoidance Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/path_candidate/ext_request_lane_change_left + Value: /planning/path_candidate/avoidance Value: true View Path: Alpha: 0.30000001192092896 @@ -1082,13 +1060,13 @@ Visualization Manager: - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true - Name: PathChangeCandidate_Avoidance + Name: PathChangeCandidate_PullOut Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/path_candidate/avoidance + Value: /planning/path_candidate/pull_out Value: true View Path: Alpha: 0.30000001192092896 @@ -1105,13 +1083,13 @@ Visualization Manager: - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true - Name: PathChangeCandidate_PullOut + Name: PathChangeCandidate_PullOver Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/path_candidate/pull_out + Value: /planning/path_candidate/pull_over Value: true View Path: Alpha: 0.30000001192092896 @@ -1125,29 +1103,20 @@ Visualization Manager: Constant Color: false Scale: 0.30000001192092896 Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 + - Class: rviz_default_plugins/MarkerArray Enabled: true - Name: PathChangeCandidate_PullOver + Name: Bound + Namespaces: + left_bound: true + right_bound: true Topic: Depth: 5 Durability Policy: Volatile + Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/path_candidate/pull_over + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/bound Value: true - View Path: - Alpha: 0.30000001192092896 - Color: 115; 210; 22 - Constant Color: false - Value: true - Width: 2 - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - Class: rviz_common/Group Displays: - Class: rviz_default_plugins/MarkerArray @@ -1174,18 +1143,6 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/crosswalk Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (Walkway) - 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/virtual_wall/walkway - Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true Name: VirtualWall (DetectionArea) @@ -1295,13 +1252,9 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/run_out Value: true - Enabled: true - Name: VirtualWall - - Class: rviz_common/Group - Displays: - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Arrow + Enabled: true + Name: VirtualWall (SpeedBump) Namespaces: {} Topic: @@ -1309,11 +1262,15 @@ Visualization Manager: 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 + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/speed_bump + Value: true + Enabled: true + Name: VirtualWall + - Class: rviz_common/Group + Displays: - Class: rviz_default_plugins/MarkerArray Enabled: false - Name: Crosswalk + Name: Arrow Namespaces: {} Topic: @@ -1321,11 +1278,11 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path Value: false - Class: rviz_default_plugins/MarkerArray Enabled: false - Name: Walkway + Name: Crosswalk Namespaces: {} Topic: @@ -1333,7 +1290,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/walkway + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk Value: false - Class: rviz_default_plugins/MarkerArray Enabled: false @@ -1515,6 +1472,18 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/sideshift Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: SpeedBump + 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/speed_bump + Value: false Enabled: false Name: DebugMarker Enabled: true @@ -1582,62 +1551,10 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/virtual_wall Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (ObstacleCruise) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/virtual_wall - Value: true Enabled: true Name: VirtualWall - Class: rviz_common/Group Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: ObstacleStop - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker - Value: true - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: CruiseVirtualWall - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/cruise/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: DebugMarker - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/marker - Value: true - Enabled: true - Name: ObstacleCruise - Class: rviz_common/Group Displays: - Class: rviz_default_plugins/MarkerArray @@ -1693,6 +1610,18 @@ Visualization Manager: Value: false Enabled: true Name: SurroundObstacleChecker + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: ObstacleStop + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker + Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true Name: ObstacleAvoidance diff --git a/autoware_launch/system_launch.drawio.svg b/autoware_launch/system_launch.drawio.svg deleted file mode 100644 index 334012a85b..0000000000 --- a/autoware_launch/system_launch.drawio.svg +++ /dev/null @@ -1,308 +0,0 @@ - - - - - - - - - - - - - - - -
    -
    -
    - system.launch.xml -
    -
    -
    - package: system_launch -
    -
    -
    -
    -
    - system.launch.xml... -
    -
    - - - - -
    -
    -
    - system_monitor.launch.py -
    -
    -
    package: system_monitor
    -
    -
    -
    -
    - system_monitor.launch.py... -
    -
    - - - - -
    -
    -
    - launch name -
    -
    -
    - package: package name -
    -
    -
    -
    -
    - launch name... -
    -
    - - - - -
    -
    -
    - ex: -
    -
    -
    -
    - ex: -
    -
    - - - - -
    -
    -
    - node name -
    -
    -
    - package: package name -
    -
    -
    -
    -
    - node name... -
    -
    - - - - -
    -
    -
    - other name -
    -
    -
    - package: package name -
    -
    -
    -
    -
    - other name... -
    -
    - - - - -
    -
    -
    - component_state_monitor.launch.py -
    -
    -
    - package: - component_state_monitor -
    -
    -
    -
    -
    - component_state_monitor.launch.py... -
    -
    - - - - - -
    -
    -
    - online -
    -
    -
    -
    - online -
    -
    - - - - - -
    -
    -
    - planning_simulation -
    -
    -
    -
    - planning_simulation -
    -
    - - - - -
    -
    -
    - $(var run_mode) -
    -
    -
    -
    - $(var run_mode) -
    -
    - - - - -
    -
    -
    - autoware_error_monitor.launch.xml -
    -
    -
    package: autoware_error_monitor
    -
    -
    -
    -
    - args: config_file = - autoware_error_monitor.param.yaml -
    -
    -
    -
    -
    - autoware_error_monitor.launch.xml... -
    -
    - - - - -
    -
    -
    - autoware_error_monitor.launch.xml -
    -
    -
    package: autoware_error_monitor
    -
    -
    -
    -
    - args: config_file = - autoware_error_monitor.planning_simulation.param.yaml -
    -
    -
    -
    -
    - autoware_error_monitor.launch.xml... -
    -
    - - - - -
    -
    -
    - emergency_handler.launch.xml -
    -
    -
    package: emergency_handler
    -
    -
    -
    -
    - emergency_handler.launch.xml... -
    -
    -
    - - - - Viewer does not support full SVG 1.1 - - -
    diff --git a/build_depends.repos b/build_depends.repos index 5e650722cd..ec3fecccd6 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -1,5 +1,5 @@ repositories: - tier4_ament_lint: + autoware_common: type: git - url: https://github.com/tier4/tier4_ament_lint.git + url: https://github.com/autowarefoundation/autoware_common.git version: main From f554365bb552c8a6254a57a4e91a5f72aab09896 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Fri, 17 Feb 2023 19:22:07 +0900 Subject: [PATCH 795/851] chore(run_out): update parameter for mandatory detection area (#770) Signed-off-by: Tomohito Ando --- .../run_out.param.yaml | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml index ccf90a0b29..f9668549f2 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml @@ -15,15 +15,20 @@ margin_behind: 0.5 # [m] ahead margin for detection area length margin_ahead: 1.0 # [m] behind margin for detection area length + # This area uses points not filtered by vector map to ensure safety + mandatory_area: + decel_jerk: -1.2 # [m/s^3] deceleration jerk for obstacles in this area + # parameter to create abstracted dynamic obstacles dynamic_obstacle: - min_vel_kmph: 0.0 # [km/h] minimum velocity for dynamic obstacles - max_vel_kmph: 5.0 # [km/h] maximum velocity for dynamic obstacles - diameter: 0.1 # [m] diameter of obstacles. used for creating dynamic obstacles from points - height: 2.0 # [m] height of obstacles. used for creating dynamic obstacles from points - max_prediction_time: 10.0 # [sec] create predicted path until this time - time_step: 0.5 # [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path - points_interval: 0.1 # [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method + use_mandatory_area: false # [-] whether to use mandatory detection area + min_vel_kmph: 0.0 # [km/h] minimum velocity for dynamic obstacles + max_vel_kmph: 5.0 # [km/h] maximum velocity for dynamic obstacles + diameter: 0.1 # [m] diameter of obstacles. used for creating dynamic obstacles from points + height: 2.0 # [m] height of obstacles. used for creating dynamic obstacles from points + max_prediction_time: 10.0 # [sec] create predicted path until this time + time_step: 0.5 # [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path + points_interval: 0.1 # [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method # approach if ego has stopped in the front of the obstacle for a certain amount of time approaching: From ef7cd4ef4e9f350fb039b89201510a088a14a525 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 20 Feb 2023 13:09:16 +0900 Subject: [PATCH 796/851] feat: use tier4/main by default for sync (#783) * feat: use tier4/universe by default for sync Signed-off-by: Takayuki Murooka * rename branch: tier4/universe -> tier4/main Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../workflows/sync-awf-autoware-launch.yaml | 2 +- .github/workflows/sync-awf-latest-s1.yaml | 4 +-- .github/workflows/sync-awf-latest-x1.yaml | 4 +-- .github/workflows/sync-awf-latest-x2.yaml | 4 +-- .github/workflows/sync-awf-latest-xx1.yaml | 4 +-- .github/workflows/sync-awf-latest.yaml | 31 ------------------- .github/workflows/sync-upstream.yaml | 4 +-- 7 files changed, 11 insertions(+), 42 deletions(-) delete mode 100644 .github/workflows/sync-awf-latest.yaml diff --git a/.github/workflows/sync-awf-autoware-launch.yaml b/.github/workflows/sync-awf-autoware-launch.yaml index d1fd166e87..40be33dc41 100644 --- a/.github/workflows/sync-awf-autoware-launch.yaml +++ b/.github/workflows/sync-awf-autoware-launch.yaml @@ -20,7 +20,7 @@ jobs: uses: autowarefoundation/autoware-github-actions/sync-branches@v1 with: token: ${{ steps.generate-token.outputs.token }} - base-branch: awf-latest + base-branch: tier4/main sync-pr-branch: sync-awf-autoware-launch sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git sync-target-branch: main diff --git a/.github/workflows/sync-awf-latest-s1.yaml b/.github/workflows/sync-awf-latest-s1.yaml index f34ce0ffa6..c14d001c61 100644 --- a/.github/workflows/sync-awf-latest-s1.yaml +++ b/.github/workflows/sync-awf-latest-s1.yaml @@ -22,8 +22,8 @@ jobs: token: ${{ steps.generate-token.outputs.token }} base-branch: awf-latest-s1 sync-pr-branch: sync-awf-latest-s1 - sync-target-repository: https://github.com/tier4/autoware_launch.git - sync-target-branch: awf-latest + sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git + sync-target-branch: main pr-title: "chore: sync awf-latest-s1" pr-labels: | bot diff --git a/.github/workflows/sync-awf-latest-x1.yaml b/.github/workflows/sync-awf-latest-x1.yaml index c51a13e917..c348e6d853 100644 --- a/.github/workflows/sync-awf-latest-x1.yaml +++ b/.github/workflows/sync-awf-latest-x1.yaml @@ -22,8 +22,8 @@ jobs: token: ${{ steps.generate-token.outputs.token }} base-branch: awf-latest-x1 sync-pr-branch: sync-awf-latest-x1 - sync-target-repository: https://github.com/tier4/autoware_launch.git - sync-target-branch: awf-latest + sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git + sync-target-branch: main pr-title: "chore: sync awf-latest-x1" pr-labels: | bot diff --git a/.github/workflows/sync-awf-latest-x2.yaml b/.github/workflows/sync-awf-latest-x2.yaml index 910c5e8598..97ed22a5f7 100644 --- a/.github/workflows/sync-awf-latest-x2.yaml +++ b/.github/workflows/sync-awf-latest-x2.yaml @@ -22,8 +22,8 @@ jobs: token: ${{ steps.generate-token.outputs.token }} base-branch: awf-latest-x2 sync-pr-branch: sync-awf-latest-x2 - sync-target-repository: https://github.com/tier4/autoware_launch.git - sync-target-branch: awf-latest + sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git + sync-target-branch: main pr-title: "chore: sync awf-latest-x2" pr-labels: | bot diff --git a/.github/workflows/sync-awf-latest-xx1.yaml b/.github/workflows/sync-awf-latest-xx1.yaml index f6d9da8591..6b6432b55e 100644 --- a/.github/workflows/sync-awf-latest-xx1.yaml +++ b/.github/workflows/sync-awf-latest-xx1.yaml @@ -22,8 +22,8 @@ jobs: token: ${{ steps.generate-token.outputs.token }} base-branch: awf-latest-xx1 sync-pr-branch: sync-awf-latest-xx1 - sync-target-repository: https://github.com/tier4/autoware_launch.git - sync-target-branch: awf-latest + sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git + sync-target-branch: main pr-title: "chore: sync awf-latest-xx1" pr-labels: | bot diff --git a/.github/workflows/sync-awf-latest.yaml b/.github/workflows/sync-awf-latest.yaml deleted file mode 100644 index 6f905ef9e8..0000000000 --- a/.github/workflows/sync-awf-latest.yaml +++ /dev/null @@ -1,31 +0,0 @@ -name: sync-awf-latest - -on: - schedule: - - cron: 0 0 * * * - workflow_dispatch: - -jobs: - sync-awf-latest: - runs-on: ubuntu-latest - steps: - - name: Generate token - id: generate-token - uses: tibdex/github-app-token@v1 - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.PRIVATE_KEY }} - - - name: Run sync-branches - uses: autowarefoundation/autoware-github-actions/sync-branches@v1 - with: - token: ${{ steps.generate-token.outputs.token }} - base-branch: tier4/universe - sync-pr-branch: sync-awf-latest - sync-target-repository: https://github.com/tier4/autoware_launch.git - sync-target-branch: awf-latest - pr-title: "chore: sync awf-latest" - pr-labels: | - bot - sync-awf-latest - auto-merge-method: merge diff --git a/.github/workflows/sync-upstream.yaml b/.github/workflows/sync-upstream.yaml index 66eb180976..0464ee742c 100644 --- a/.github/workflows/sync-upstream.yaml +++ b/.github/workflows/sync-upstream.yaml @@ -20,10 +20,10 @@ jobs: uses: autowarefoundation/autoware-github-actions/sync-branches@v1 with: token: ${{ steps.generate-token.outputs.token }} - base-branch: tier4/universe + base-branch: tier4/main sync-pr-branch: sync-upstream sync-target-repository: https://github.com/tier4/autoware_launch.git - sync-target-branch: tier4/universe + sync-target-branch: tier4/main pr-title: "chore: sync upstream" pr-labels: | bot From fc23da9fda8cb2b59dfe1bd85c9f81c908b33b69 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 20 Feb 2023 14:47:47 +0900 Subject: [PATCH 797/851] chore: remove unnecessary sync (#800) Signed-off-by: Takayuki Murooka --- .github/sync-launch-files.yaml | 13 -- .github/sync-param-files.yaml | 157 ------------------ .github/update-sync-param-files.py | 80 --------- .github/workflows/sync-launch-files.yaml | 37 ----- .github/workflows/sync-param-files.yaml | 26 --- .../workflows/update-sync-param-files.yaml | 54 ------ 6 files changed, 367 deletions(-) delete mode 100644 .github/sync-launch-files.yaml delete mode 100644 .github/sync-param-files.yaml delete mode 100644 .github/update-sync-param-files.py delete mode 100644 .github/workflows/sync-launch-files.yaml delete mode 100644 .github/workflows/sync-param-files.yaml delete mode 100644 .github/workflows/update-sync-param-files.yaml diff --git a/.github/sync-launch-files.yaml b/.github/sync-launch-files.yaml deleted file mode 100644 index 861381e272..0000000000 --- a/.github/sync-launch-files.yaml +++ /dev/null @@ -1,13 +0,0 @@ -- repository: autowarefoundation/autoware_launch - files: - - source: autoware_launch/launch/autoware.launch.xml - - source: autoware_launch/launch/e2e_simulator.launch.xml - - source: autoware_launch/launch/logging_simulator.launch.xml - - source: autoware_launch/launch/planning_simulator.launch.xml - - source: autoware_launch/launch/pointcloud_container.launch.py - - source: autoware_launch/rviz/autoware.rviz - - source: autoware_launch/rviz/image/autoware.png - - source: autoware_launch/CMakeLists.txt - - source: autoware_launch/README.md - - source: autoware_launch/autoware_launch.drawio.svg - - source: autoware_launch/package.xml diff --git a/.github/sync-param-files.yaml b/.github/sync-param-files.yaml deleted file mode 100644 index 1b18bda91c..0000000000 --- a/.github/sync-param-files.yaml +++ /dev/null @@ -1,157 +0,0 @@ -- repository: autowarefoundation/autoware.universe - files: - # tier4_autoware_api_launch - - # tier4_control_launch - - source: launch/tier4_control_launch/config/common/nearest_search.param.yaml - dest: autoware_launch/config/tier4_control_launch/common/nearest_search.param.yaml - - source: launch/tier4_control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml - dest: autoware_launch/config/tier4_control_launch/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml - - source: launch/tier4_control_launch/config/shift_decider/shift_decider.param.yaml - dest: autoware_launch/config/tier4_control_launch/shift_decider/shift_decider.param.yaml - - source: launch/tier4_control_launch/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml - dest: autoware_launch/config/tier4_control_launch/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml - - source: launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml - dest: autoware_launch/config/tier4_control_launch/trajectory_follower/longitudinal_controller.param.yaml - - source: launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml - dest: autoware_launch/config/tier4_control_launch/trajectory_follower/lateral_controller.param.yaml - - source: launch/tier4_control_launch/config/obstacle_collision_checker/obstacle_collision_checker.param.yaml - dest: autoware_launch/config/tier4_control_launch/obstacle_collision_checker/obstacle_collision_checker.param.yaml - - # tier4_localization_launch - - source: launch/tier4_localization_launch/config/ndt_scan_matcher.param.yaml - dest: autoware_launch/config/tier4_localization_launch/ndt_scan_matcher.param.yaml - - source: launch/tier4_localization_launch/config/localization_error_monitor.param.yaml - dest: autoware_launch/config/tier4_localization_launch/localization_error_monitor.param.yaml - - source: launch/tier4_localization_launch/config/random_downsample_filter.param.yaml - dest: autoware_launch/config/tier4_localization_launch/random_downsample_filter.param.yaml - - source: launch/tier4_localization_launch/config/crop_box_filter_measurement_range.param.yaml - dest: autoware_launch/config/tier4_localization_launch/crop_box_filter_measurement_range.param.yaml - - source: launch/tier4_localization_launch/config/voxel_grid_filter.param.yaml - dest: autoware_launch/config/tier4_localization_launch/voxel_grid_filter.param.yaml - - # tier4_map_launch - - source: launch/tier4_map_launch/config/pointcloud_map_loader.param.yaml - dest: autoware_launch/config/tier4_map_launch/pointcloud_map_loader.param.yaml - - # tier4_perception_launch - - source: launch/tier4_perception_launch/config/object_recognition/detection/object_position_filter.param.yaml - dest: autoware_launch/config/tier4_perception_launch/object_recognition/detection/object_position_filter.param.yaml - - source: launch/tier4_perception_launch/config/object_recognition/detection/object_lanelet_filter.param.yaml - dest: autoware_launch/config/tier4_perception_launch/object_recognition/detection/object_lanelet_filter.param.yaml - - source: launch/tier4_perception_launch/config/object_recognition/detection/pointcloud_map_filter.param.yaml - dest: autoware_launch/config/tier4_perception_launch/object_recognition/detection/pointcloud_map_filter.param.yaml - - source: launch/tier4_perception_launch/config/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml - dest: autoware_launch/config/tier4_perception_launch/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml - - source: launch/tier4_perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml - dest: autoware_launch/config/tier4_perception_launch/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml - - # tier4_planning_launch - - source: launch/tier4_planning_launch/config/scenario_planning/common/common.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/common.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/common/nearest_search.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/nearest_search.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/common/motion_velocity_smoother/L2.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/motion_velocity_smoother/L2.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_traffic_light.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/lane_change_planner/lane_change_planner.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/obstacle_velocity_limiter.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml - - source: launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml - dest: autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml - - # tier4_sensing_launch - - # tier4_simulator_launch - - source: launch/tier4_simulator_launch/config/fault_injection.param.yaml - dest: autoware_launch/config/tier4_simulator_launch/fault_injection.param.yaml - - # tier4_system_launch - - source: launch/tier4_system_launch/config/emergency_handler/emergency_handler.param.yaml - dest: autoware_launch/config/tier4_system_launch/emergency_handler/emergency_handler.param.yaml - - source: launch/tier4_system_launch/config/mrm_emergency_stop_operator/mrm_emergency_stop_operator.param.yaml - dest: autoware_launch/config/tier4_system_launch/mrm_emergency_stop_operator/mrm_emergency_stop_operator.param.yaml - - source: launch/tier4_system_launch/config/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator.param.yaml - dest: autoware_launch/config/tier4_system_launch/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator.param.yaml - - source: launch/tier4_system_launch/config/system_error_monitor/system_error_monitor.param.yaml - dest: autoware_launch/config/tier4_system_launch/system_error_monitor/system_error_monitor.param.yaml - - source: launch/tier4_system_launch/config/system_error_monitor/system_error_monitor.planning_simulation.param.yaml - dest: autoware_launch/config/tier4_system_launch/system_error_monitor/system_error_monitor.planning_simulation.param.yaml - - source: launch/tier4_system_launch/config/system_error_monitor/diagnostic_aggregator/vehicle.param.yaml - dest: autoware_launch/config/tier4_system_launch/system_error_monitor/diagnostic_aggregator/vehicle.param.yaml - - source: launch/tier4_system_launch/config/system_monitor/gpu_monitor.param.yaml - dest: autoware_launch/config/tier4_system_launch/system_monitor/gpu_monitor.param.yaml - - source: launch/tier4_system_launch/config/system_monitor/ntp_monitor.param.yaml - dest: autoware_launch/config/tier4_system_launch/system_monitor/ntp_monitor.param.yaml - - source: launch/tier4_system_launch/config/system_monitor/mem_monitor.param.yaml - dest: autoware_launch/config/tier4_system_launch/system_monitor/mem_monitor.param.yaml - - source: launch/tier4_system_launch/config/system_monitor/voltage_monitor.param.yaml - dest: autoware_launch/config/tier4_system_launch/system_monitor/voltage_monitor.param.yaml - - source: launch/tier4_system_launch/config/system_monitor/net_monitor.param.yaml - dest: autoware_launch/config/tier4_system_launch/system_monitor/net_monitor.param.yaml - - source: launch/tier4_system_launch/config/system_monitor/process_monitor.param.yaml - dest: autoware_launch/config/tier4_system_launch/system_monitor/process_monitor.param.yaml - - source: launch/tier4_system_launch/config/system_monitor/cpu_monitor.param.yaml - dest: autoware_launch/config/tier4_system_launch/system_monitor/cpu_monitor.param.yaml - - source: launch/tier4_system_launch/config/system_monitor/hdd_monitor.param.yaml - dest: autoware_launch/config/tier4_system_launch/system_monitor/hdd_monitor.param.yaml - - # tier4_vehicle_launch diff --git a/.github/update-sync-param-files.py b/.github/update-sync-param-files.py deleted file mode 100644 index 707909cdd1..0000000000 --- a/.github/update-sync-param-files.py +++ /dev/null @@ -1,80 +0,0 @@ -import argparse -import dataclasses -from pathlib import Path -from typing import List -from typing import Optional - -import git - -""" -This module updates `sync-param-files.yaml` based on the launch parameter files in `autoware.universe`. -""" - -REPO_NAME = "autowarefoundation/autoware.universe" -REPO_URL = f"https://github.com/{REPO_NAME}.git" -CLONE_PATH = Path("/tmp/autoware.universe") - - -@dataclasses.dataclass -class FileSyncConfig: - source: str - dest: str - replace: Optional[bool] = None - delete_orphaned: Optional[bool] = None - pre_commands: Optional[str] = None - post_commands: Optional[str] = None - - -def create_tier4_launch_sync_configs(tier4_launch_package_path: Path) -> List[FileSyncConfig]: - launch_package_name = tier4_launch_package_path.name - launch_config_path = tier4_launch_package_path / "config" - - sync_configs = [] - for param_file_path in tier4_launch_package_path.glob("config/**/*.param.yaml"): - relative_param_file_path = param_file_path.relative_to(launch_config_path) - - source = param_file_path.relative_to(CLONE_PATH) - dest = Path("autoware_launch/config") / launch_package_name / relative_param_file_path - - sync_configs.append(FileSyncConfig(str(source), str(dest))) - - return sync_configs - - -def dump_sync_config(section_name: str, sync_configs: List[FileSyncConfig]) -> List[str]: - indent = 4 * " " - lines = [f"{indent}# {section_name}\n"] - for sync_config in sync_configs: - lines.append(f"{indent}- source: {sync_config.source}\n") - lines.append(f"{indent} dest: {sync_config.dest}\n") - lines.append("\n") - return lines - - -def main(): - parser = argparse.ArgumentParser() - parser.add_argument("sync_param_files_path", type=Path, help="path to sync-param-files.yaml") - args = parser.parse_args() - - # Clone Autoware - if not CLONE_PATH.exists(): - git.Repo.clone_from(REPO_URL, CLONE_PATH) - - # Create sync config for tier4_*_launch - tier4_launch_package_paths = sorted( - CLONE_PATH.glob("launch/tier4_*_launch"), key=lambda p: p.name - ) - tier4_launch_sync_configs_map = { - p.name: create_tier4_launch_sync_configs(p) for p in tier4_launch_package_paths - } - - # Create sync-param-files.yaml - with open(args.sync_param_files_path, "w") as f: - f.write(f"- repository: {REPO_NAME}\n") - f.write(" files:\n") - for section_name, sync_config in tier4_launch_sync_configs_map.items(): - f.writelines(dump_sync_config(section_name, sync_config)) - - -if __name__ == "__main__": - main() diff --git a/.github/workflows/sync-launch-files.yaml b/.github/workflows/sync-launch-files.yaml deleted file mode 100644 index 1c54e26f3e..0000000000 --- a/.github/workflows/sync-launch-files.yaml +++ /dev/null @@ -1,37 +0,0 @@ -name: sync-launch-files - -on: - schedule: - - cron: 0 0 * * * - workflow_dispatch: - -jobs: - check-secret: - uses: autowarefoundation/autoware-github-actions/.github/workflows/check-secret.yaml@v1 - secrets: - secret: ${{ secrets.APP_ID }} - - sync-files: - needs: check-secret - if: ${{ needs.check-secret.outputs.set == 'true' }} - runs-on: ubuntu-latest - steps: - - name: Generate token - id: generate-token - uses: tibdex/github-app-token@v1 - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.PRIVATE_KEY }} - - - name: Run sync-files - uses: autowarefoundation/autoware-github-actions/sync-files@v1 - with: - token: ${{ steps.generate-token.outputs.token }} - config: .github/sync-launch-files.yaml - pr-branch: sync-launch-files - pr-title: "chore: sync launch files" - pr-commit-message: "chore: sync launch files" - pr-labels: | - bot - sync-launch-files - auto-merge-method: squash diff --git a/.github/workflows/sync-param-files.yaml b/.github/workflows/sync-param-files.yaml deleted file mode 100644 index c119083f9d..0000000000 --- a/.github/workflows/sync-param-files.yaml +++ /dev/null @@ -1,26 +0,0 @@ -name: sync-param-files - -on: - schedule: - - cron: 0 0 * * * - workflow_dispatch: - -jobs: - sync-param-files: - runs-on: ubuntu-latest - steps: - - name: Generate token - id: generate-token - uses: tibdex/github-app-token@v1 - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.PRIVATE_KEY }} - - - name: Run sync-files - uses: autowarefoundation/autoware-github-actions/sync-files@v1 - with: - token: ${{ steps.generate-token.outputs.token }} - config: .github/sync-param-files.yaml - pr-branch: sync-param-files - pr-title: "chore: sync param files" - pr-commit-message: "chore: sync param files" diff --git a/.github/workflows/update-sync-param-files.yaml b/.github/workflows/update-sync-param-files.yaml deleted file mode 100644 index fbce54b07f..0000000000 --- a/.github/workflows/update-sync-param-files.yaml +++ /dev/null @@ -1,54 +0,0 @@ -name: update-sync-param-files - -on: - schedule: - - cron: 0 0 * * * - workflow_dispatch: - -jobs: - update-sync-param-files: - runs-on: ubuntu-latest - steps: - - name: Generate token - id: generate-token - uses: tibdex/github-app-token@v1 - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.PRIVATE_KEY }} - - - name: Check out repository - uses: actions/checkout@v3 - - - name: Install GitPython - run: | - pip3 install GitPython - shell: bash - - - name: Generate sync-param-files.yaml - run: | - python3 .github/update-sync-param-files.py .github/sync-param-files.yaml - - - name: Create PR - id: create-pr - uses: peter-evans/create-pull-request@v4 - with: - token: ${{ steps.generate-token.outputs.token }} - base: ${{ github.event.repository.default_branch }} - branch: update-sync-param-files - title: "chore: update sync-param-files.yaml" - commit-message: "chore: update sync-param-files.yaml" - body: ${{ steps.create-pr-body.outputs.body }} - - - name: Check outputs - run: | - echo "Pull Request Number - ${{ steps.create-pr.outputs.pull-request-number }}" - echo "Pull Request URL - ${{ steps.create-pr.outputs.pull-request-url }}" - shell: bash - - - name: Enable auto-merge - if: ${{ steps.create-pr.outputs.pull-request-operation == 'created' }} - uses: peter-evans/enable-pull-request-automerge@v2 - with: - token: ${{ steps.generate-token.outputs.token }} - pull-request-number: ${{ steps.create-pr.outputs.pull-request-number }} - merge-method: squash From d1a56558775f4865153e1cb37a3994a37efb1210 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 20 Feb 2023 16:27:16 +0900 Subject: [PATCH 798/851] feat: rename tier4 and awf sync upstream (#802) Signed-off-by: Takayuki Murooka --- ...nc-awf-autoware-launch.yaml => sync-awf-upstream.yaml} | 8 ++++---- .../{sync-upstream.yaml => sync-tier4-upstream.yaml} | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) rename .github/workflows/{sync-awf-autoware-launch.yaml => sync-awf-upstream.yaml} (84%) rename .github/workflows/{sync-upstream.yaml => sync-tier4-upstream.yaml} (85%) diff --git a/.github/workflows/sync-awf-autoware-launch.yaml b/.github/workflows/sync-awf-upstream.yaml similarity index 84% rename from .github/workflows/sync-awf-autoware-launch.yaml rename to .github/workflows/sync-awf-upstream.yaml index 40be33dc41..d2ee862fd4 100644 --- a/.github/workflows/sync-awf-autoware-launch.yaml +++ b/.github/workflows/sync-awf-upstream.yaml @@ -1,4 +1,4 @@ -name: sync-awf-autoware-launch +name: sync-awf-upstream on: schedule: @@ -6,7 +6,7 @@ on: workflow_dispatch: jobs: - sync-awf-autoware-launch: + sync-awf-upstream: runs-on: ubuntu-latest steps: - name: Generate token @@ -21,11 +21,11 @@ jobs: with: token: ${{ steps.generate-token.outputs.token }} base-branch: tier4/main - sync-pr-branch: sync-awf-autoware-launch + sync-pr-branch: sync-awf-upstream sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git sync-target-branch: main pr-title: "chore: sync awf/autoware_launch" pr-labels: | bot - sync-awf-autoware-launch + sync-awf-upstream auto-merge-method: merge diff --git a/.github/workflows/sync-upstream.yaml b/.github/workflows/sync-tier4-upstream.yaml similarity index 85% rename from .github/workflows/sync-upstream.yaml rename to .github/workflows/sync-tier4-upstream.yaml index 0464ee742c..b7dc824f8a 100644 --- a/.github/workflows/sync-upstream.yaml +++ b/.github/workflows/sync-tier4-upstream.yaml @@ -1,4 +1,4 @@ -name: sync-upstream +name: sync-tier4-upstream on: schedule: @@ -6,7 +6,7 @@ on: workflow_dispatch: jobs: - sync-upstream: + sync-tier4-upstream: runs-on: ubuntu-latest steps: - name: Generate token @@ -21,11 +21,11 @@ jobs: with: token: ${{ steps.generate-token.outputs.token }} base-branch: tier4/main - sync-pr-branch: sync-upstream + sync-pr-branch: sync-tier4-upstream sync-target-repository: https://github.com/tier4/autoware_launch.git sync-target-branch: tier4/main pr-title: "chore: sync upstream" pr-labels: | bot - sync-upstream + sync-tier4-upstream auto-merge-method: merge From c47af32fe6ea0b62cd4ecee5ed682ba1ea2a486c Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 28 Feb 2023 09:39:55 +0900 Subject: [PATCH 799/851] chore: sync awf/autoware_launch (#820) feat(obstacle_stop_planner): add margin behind goal (#228) Signed-off-by: kosuke55 Co-authored-by: Kosuke Takeuchi --- .../obstacle_stop_planner/obstacle_stop_planner.param.yaml | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml index 141297a2a7..a68a760166 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml @@ -15,9 +15,10 @@ stop_planner: # params for stop position stop_position: - max_longitudinal_margin: 5.0 # stop margin distance from obstacle on the path [m] - min_longitudinal_margin: 5.0 # stop margin distance when any other stop point is inserted in stop margin [m] - hold_stop_margin_distance: 0.0 # the ego keeps stopping if the ego is in this margin [m] + max_longitudinal_margin: 5.0 # stop margin distance from obstacle on the path [m] + max_longitudinal_margin_behind_goal: 3.0 # stop margin distance from obstacle behind goal on the path [m] + min_longitudinal_margin: 5.0 # stop margin distance when any other stop point is inserted in stop margin [m] + hold_stop_margin_distance: 0.0 # the ego keeps stopping if the ego is in this margin [m] # params for detection area detection_area: From cc2dbd7b4d0c878cf9bbd1a70be74f85311c746e Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Mon, 6 Mar 2023 10:41:55 +0900 Subject: [PATCH 800/851] fix(autoware_launch): fix api options (#839) * fix(autoware_launch): fix api options Signed-off-by: Takagi, Isamu * style(pre-commit): autofix * fix: typo Signed-off-by: Takagi, Isamu --------- Signed-off-by: Takagi, Isamu Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../components/tier4_autoware_api_component.launch.xml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml b/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml index 1c7b520108..bc582fbb9a 100644 --- a/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml +++ b/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml @@ -1,7 +1,8 @@ - - + + + From 000b9b20a72dfee25272b4900846556a8b846f25 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Tue, 4 Apr 2023 14:52:37 +0900 Subject: [PATCH 801/851] chore: sync files (#214) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/PULL_REQUEST_TEMPLATE/small-change.md | 34 +++++++++++++++++++ .../build-and-test-differential.yaml | 2 +- .github/workflows/github-release.yaml | 8 ++--- .github/workflows/pre-commit.yaml | 5 --- 4 files changed, 39 insertions(+), 10 deletions(-) create mode 100644 .github/PULL_REQUEST_TEMPLATE/small-change.md diff --git a/.github/PULL_REQUEST_TEMPLATE/small-change.md b/.github/PULL_REQUEST_TEMPLATE/small-change.md new file mode 100644 index 0000000000..527c8ed81f --- /dev/null +++ b/.github/PULL_REQUEST_TEMPLATE/small-change.md @@ -0,0 +1,34 @@ +## Description + + + +## Tests performed + + + + +Not applicable. + +## Pre-review checklist for the PR author + +The PR author **must** check the checkboxes below when creating the PR. + +- [ ] I've confirmed the [contribution guidelines]. +- [ ] The PR follows the [pull request guidelines]. + +## In-review checklist for the PR reviewers + +The PR reviewers **must** check the checkboxes below before approval. + +- [ ] The PR follows the [pull request guidelines]. + +## Post-review checklist for the PR author + +The PR author **must** check the checkboxes below before merging. + +- [ ] There are no open discussions or they are tracked via tickets. + +After all checkboxes are checked, anyone who has write access can merge the PR. + +[contribution guidelines]: https://autowarefoundation.github.io/autoware-documentation/main/contributing/ +[pull request guidelines]: https://autowarefoundation.github.io/autoware-documentation/main/contributing/pull-request-guidelines/ diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 24b34530f0..8eeb1de069 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -74,7 +74,7 @@ jobs: - name: Get modified files id: get-modified-files - uses: tj-actions/changed-files@v34 + uses: tj-actions/changed-files@v35 with: files: | **/*.cpp diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 19e1e9c12e..95ebb8725f 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -26,8 +26,8 @@ jobs: REF_NAME="${{ github.ref_name }}" fi - echo ::set-output name=ref-name::"$REF_NAME" - echo ::set-output name=tag-name::"${REF_NAME#beta/}" + echo "ref-name=$REF_NAME" >> $GITHUB_OUTPUT + echo "tag-name=${REF_NAME#beta/}" >> $GITHUB_OUTPUT - name: Check out repository uses: actions/checkout@v3 @@ -39,7 +39,7 @@ jobs: id: set-target-name run: | if [[ "${{ steps.set-tag-name.outputs.ref-name }}" =~ "beta/" ]]; then - echo ::set-output name=target-name::"${{ steps.set-tag-name.outputs.ref-name }}" + echo "target-name=${{ steps.set-tag-name.outputs.ref-name }}" >> $GITHUB_OUTPUT fi - name: Create a local tag for beta branches @@ -62,7 +62,7 @@ jobs: verb=edit fi - echo ::set-output name=verb::"$verb" + echo "verb=$verb" >> $GITHUB_OUTPUT env: GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml index bda722c87e..b231dbda87 100644 --- a/.github/workflows/pre-commit.yaml +++ b/.github/workflows/pre-commit.yaml @@ -20,11 +20,6 @@ jobs: with: ref: ${{ github.event.pull_request.head.ref }} - - name: Set git config - uses: autowarefoundation/autoware-github-actions/set-git-config@v1 - with: - token: ${{ steps.generate-token.outputs.token }} - - name: Run pre-commit uses: autowarefoundation/autoware-github-actions/pre-commit@v1 with: From 55c4c270a6e96ffc08d1685a21840a5dba6c0034 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 4 Apr 2023 15:44:53 +0900 Subject: [PATCH 802/851] feat(autoware_launch): ext_lane_change -> external_lane_change in rtc (#274) * fix Signed-off-by: Takayuki Murooka * empty commit Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml index 0e3391e69e..f38becc39f 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml @@ -7,8 +7,8 @@ - "intersection" - "no_stopping_area" - "traffic_light" - - "ext_request_lane_change_left" - - "ext_request_lane_change_right" + - "external_request_lane_change_left" + - "external_request_lane_change_right" - "lane_change_left" - "lane_change_right" - "avoidance_left" From 4079dc36adde17d3a14d938959ae881b4c7ed309 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 4 Apr 2023 20:38:16 +0900 Subject: [PATCH 803/851] fix(autoware_launch): fix external lane change name (#276) * fix(autoware_launch): fix external lane change name Signed-off-by: Takayuki Murooka * update rviz Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../behavior_path_planner/scene_module_manager.param.yaml | 4 ++-- autoware_launch/rviz/autoware.rviz | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml index 098af56ede..31b1d99348 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml @@ -3,13 +3,13 @@ # NOTE: The smaller the priority number is, the higher the module priority is. /**: ros__parameters: - ext_request_lane_change_left: + external_request_lane_change_left: enable_module: false enable_simultaneous_execution: false priority: 6 max_module_size: 1 - ext_request_lane_change_right: + external_request_lane_change_right: enable_module: false enable_simultaneous_execution: false priority: 6 diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 022a24f72f..e7ce7b6371 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1181,7 +1181,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/path_candidate/ext_request_lane_change_right + Value: /planning/path_candidate/external_request_lane_change_right Value: true View Path: Alpha: 0.30000001192092896 @@ -1204,7 +1204,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/path_candidate/ext_request_lane_change_left + Value: /planning/path_candidate/external_request_lane_change_left Value: true View Path: Alpha: 0.30000001192092896 From 0aa6fc89fa03ab13a24b6bda3407bcdfa6399643 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi Date: Wed, 5 Apr 2023 15:34:06 +0900 Subject: [PATCH 804/851] feat: update sync files Signed-off-by: Shumpei Wakabayashi --- .github/sync-files.yaml | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index dad19011ef..4deb334463 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -1,7 +1,17 @@ - repository: autowarefoundation/autoware files: + - source: CODE_OF_CONDUCT.md + - source: CONTRIBUTING.md + - source: DISCLAIMER.md + - source: LICENSE + - source: .github/ISSUE_TEMPLATE/bug.yaml + - source: .github/ISSUE_TEMPLATE/config.yml + - source: .github/ISSUE_TEMPLATE/task.yaml + - source: .github/PULL_REQUEST_TEMPLATE.md + - source: .github/PULL_REQUEST_TEMPLATE/small-change.md + - source: .github/PULL_REQUEST_TEMPLATE/standard-change.md - source: .github/dependabot.yaml - - source: .github/workflows/backport.yaml + - source: .github/stale.yml - source: .github/workflows/github-release.yaml - source: .github/workflows/pre-commit.yaml - source: .github/workflows/pre-commit-optional.yaml @@ -21,8 +31,3 @@ - source: .github/workflows/build-and-test.yaml - source: .github/workflows/build-and-test-differential.yaml - source: .github/workflows/cancel-previous-workflows.yaml - -- repository: autowarefoundation/autoware_launch - files: - - source: .github/update-sync-param-files.py - - source: .github/workflows/update-sync-param-files.yaml From a6d8f1bd050cce4525eff49d661b00ed7773cd7a Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi Date: Wed, 5 Apr 2023 15:42:42 +0900 Subject: [PATCH 805/851] feat: add backport sync Signed-off-by: Shumpei Wakabayashi --- .github/sync-files.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 4deb334463..6728792249 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -11,6 +11,7 @@ - source: .github/PULL_REQUEST_TEMPLATE/small-change.md - source: .github/PULL_REQUEST_TEMPLATE/standard-change.md - source: .github/dependabot.yaml + - source: .github/workflows/backport.yaml - source: .github/stale.yml - source: .github/workflows/github-release.yaml - source: .github/workflows/pre-commit.yaml From 8bb80664b0b474612e63a4a2b61dcb27d93477d4 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi Date: Wed, 5 Apr 2023 16:10:05 +0900 Subject: [PATCH 806/851] feat: add dispatch-release-note Signed-off-by: Shumpei Wakabayashi --- .github/dispatch-release-note.yaml | 42 ++++++++++++++++++++++++++++++ 1 file changed, 42 insertions(+) create mode 100644 .github/dispatch-release-note.yaml diff --git a/.github/dispatch-release-note.yaml b/.github/dispatch-release-note.yaml new file mode 100644 index 0000000000..8f054f77b1 --- /dev/null +++ b/.github/dispatch-release-note.yaml @@ -0,0 +1,42 @@ +name: dispatch-release-note +on: + push: + branches: + - tier4/main + workflow_dispatch: + inputs: + beta-branch-or-tag-name: + description: The name of the beta branch or tag to write release note + type: string + required: true +jobs: + dispatch-release-note: + runs-on: ubuntu-latest + name: release-repository-dispatch + steps: + - name: Set tag name + id: set-tag-name + run: | + if [ "${{ github.event_name }}" = "workflow_dispatch" ]; then + REF_NAME="${{ github.event.inputs.beta-branch-or-tag-name }}" + else + REF_NAME="${{ github.ref_name }}" + fi + echo ::set-output name=ref-name::"$REF_NAME" + echo ::set-output name=tag-name::"${REF_NAME#beta/}" + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Repository dispatch for release note + run: | + curl \ + -X POST \ + -H "Accept: application/vnd.github+json" \ + -H "Authorization: token ${{ steps.generate-token.outputs.token }}" \ + -H "X-GitHub-Api-Version: 2022-11-28" \ + "https://api.github.com/repos/tier4/update-release-notes/dispatches" \ + -d '{"event_type":"${{ steps.set-tag-name.outputs.ref-name }}"}' From a8f05b27e5509c78fb5075933d6f9a848e8101ab Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi Date: Wed, 5 Apr 2023 16:19:09 +0900 Subject: [PATCH 807/851] feat: REF_NAME_launch Signed-off-by: Shumpei Wakabayashi --- .github/dispatch-release-note.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/dispatch-release-note.yaml b/.github/dispatch-release-note.yaml index 8f054f77b1..6b5d3df78a 100644 --- a/.github/dispatch-release-note.yaml +++ b/.github/dispatch-release-note.yaml @@ -22,7 +22,7 @@ jobs: else REF_NAME="${{ github.ref_name }}" fi - echo ::set-output name=ref-name::"$REF_NAME" + echo ::set-output name=ref-name::"'$REF_NAME'_launch" echo ::set-output name=tag-name::"${REF_NAME#beta/}" - name: Generate token id: generate-token From 2b14af3022f78aba817d39276af34357fbea755b Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Wed, 5 Apr 2023 16:57:14 +0900 Subject: [PATCH 808/851] chore: sync files (#27) Signed-off-by: GitHub Co-authored-by: shmpwk --- .github/ISSUE_TEMPLATE/bug.yaml | 71 ++++++++++ .github/ISSUE_TEMPLATE/config.yml | 13 ++ .github/ISSUE_TEMPLATE/task.yaml | 42 ++++++ .github/PULL_REQUEST_TEMPLATE.md | 57 +------- .../PULL_REQUEST_TEMPLATE/standard-change.md | 42 ++++++ .github/stale.yml | 12 ++ CODE_OF_CONDUCT.md | 132 ++++++++++++++++++ CONTRIBUTING.md | 3 + DISCLAIMER.md | 46 ++++++ 9 files changed, 366 insertions(+), 52 deletions(-) create mode 100644 .github/ISSUE_TEMPLATE/bug.yaml create mode 100644 .github/ISSUE_TEMPLATE/config.yml create mode 100644 .github/ISSUE_TEMPLATE/task.yaml create mode 100644 .github/PULL_REQUEST_TEMPLATE/standard-change.md create mode 100644 .github/stale.yml create mode 100644 CODE_OF_CONDUCT.md create mode 100644 CONTRIBUTING.md create mode 100644 DISCLAIMER.md diff --git a/.github/ISSUE_TEMPLATE/bug.yaml b/.github/ISSUE_TEMPLATE/bug.yaml new file mode 100644 index 0000000000..12a857998a --- /dev/null +++ b/.github/ISSUE_TEMPLATE/bug.yaml @@ -0,0 +1,71 @@ +name: Bug +description: Report a bug +body: + - type: checkboxes + attributes: + label: Checklist + description: Confirm the following items before proceeding. If one cannot be satisfied, create a discussion thread instead. + options: + - label: I've read the [contribution guidelines](https://github.com/autowarefoundation/autoware/blob/main/CONTRIBUTING.md). + required: true + - label: I've searched other issues and no duplicate issues were found. + required: true + - label: I'm convinced that this is not my fault but a bug. + required: true + + - type: textarea + attributes: + label: Description + description: Write a brief description of the bug. + validations: + required: true + + - type: textarea + attributes: + label: Expected behavior + description: Describe the expected behavior. + validations: + required: true + + - type: textarea + attributes: + label: Actual behavior + description: Describe the actual behavior. + validations: + required: true + + - type: textarea + attributes: + label: Steps to reproduce + description: Write the steps to reproduce the bug. + placeholder: |- + 1. + 2. + 3. + validations: + required: true + + - type: textarea + attributes: + label: Versions + description: Provide the version information. You can omit this if you believe it's irrelevant. + placeholder: |- + - OS: + - ROS 2: + - Autoware: + validations: + required: false + + - type: textarea + attributes: + label: Possible causes + description: Write the possible causes if you have any ideas. + validations: + required: false + + - type: textarea + attributes: + label: Additional context + description: Add any other additional context if it exists. + validations: + required: false diff --git a/.github/ISSUE_TEMPLATE/config.yml b/.github/ISSUE_TEMPLATE/config.yml new file mode 100644 index 0000000000..48765c24a7 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/config.yml @@ -0,0 +1,13 @@ +blank_issues_enabled: false +contact_links: + - name: Question + url: https://github.com/autowarefoundation/autoware/discussions/new?category=q-a + about: Ask a question + + - name: Feature request + url: https://github.com/autowarefoundation/autoware/discussions/new?category=feature-requests + about: Send a feature request + + - name: Idea + url: https://github.com/autowarefoundation/autoware/discussions/new?category=ideas + about: Post an idea diff --git a/.github/ISSUE_TEMPLATE/task.yaml b/.github/ISSUE_TEMPLATE/task.yaml new file mode 100644 index 0000000000..cd8322f507 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/task.yaml @@ -0,0 +1,42 @@ +name: Task +description: Plan a task +body: + - type: checkboxes + attributes: + label: Checklist + description: Confirm the following items before proceeding. If one cannot be satisfied, create a discussion thread instead. + options: + - label: I've read the [contribution guidelines](https://github.com/autowarefoundation/autoware/blob/main/CONTRIBUTING.md). + required: true + - label: I've searched other issues and no duplicate issues were found. + required: true + - label: I've agreed with the maintainers that I can plan this task. + required: true + + - type: textarea + attributes: + label: Description + description: Write a brief description of the task. + validations: + required: true + + - type: textarea + attributes: + label: Purpose + description: Describe the purpose of the task. + validations: + required: true + + - type: textarea + attributes: + label: Possible approaches + description: Describe possible approaches for the task. + validations: + required: true + + - type: textarea + attributes: + label: Definition of done + description: Write the definition of done for the task. + validations: + required: true diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md index e0864cce57..97b0e95452 100644 --- a/.github/PULL_REQUEST_TEMPLATE.md +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -1,55 +1,8 @@ -## PR Type +**Note**: Confirm the [contribution guidelines](https://autowarefoundation.github.io/autoware-documentation/main/contributing/) before submitting a pull request. - +Click the `Preview` tab and select a PR template: -- New Feature -- Improvement -- Bug Fix +- [Standard change](?expand=1&template=standard-change.md) +- [Small change](?expand=1&template=small-change.md) -## Related Links - - - -## Description - - - -## Review Procedure - - - -## Remarks - - - -## Pre-Review Checklist for the PR Author - -**PR Author should check the checkboxes below when creating the PR.** - -- [ ] Code follows [coding guidelines][coding-guidelines] -- [ ] Assign PR to reviewer - -## Checklist for the PR Reviewer - -**Reviewers should check the checkboxes below before approval.** - -- [ ] Commits are properly organized and messages are according to the guideline -- [ ] Code follows [coding guidelines][coding-guidelines] -- [ ] (Optional) Unit tests have been written for new behavior -- [ ] PR title describes the changes - -## Post-Review Checklist for the PR Author - -**PR Author should check the checkboxes below before merging.** - -- [ ] All open points are addressed and tracked via issues or tickets -- [ ] Write [release notes][release-notes] - -## CI Checks - -- **Build and test for PR**: Required to pass before the merge. -- **Check spelling**: NOT required to pass before the merge. It is up to the reviewer(s). See [here][spell-check-dict] if you want to add some words to the spell check dictionary. - -[coding-guidelines]: https://tier4.atlassian.net/wiki/spaces/AIP/pages/1194394777/T4 -[release-notes]: https://tier4.atlassian.net/wiki/spaces/AIP/pages/563774416 -[spell-check-dict]: https://github.com/tier4/autoware-spell-check-dict#how-to-contribute +**Do NOT send a PR with this description.** diff --git a/.github/PULL_REQUEST_TEMPLATE/standard-change.md b/.github/PULL_REQUEST_TEMPLATE/standard-change.md new file mode 100644 index 0000000000..cfdf7101b5 --- /dev/null +++ b/.github/PULL_REQUEST_TEMPLATE/standard-change.md @@ -0,0 +1,42 @@ +## Description + + + +## Related links + + + +## Tests performed + + + +## Notes for reviewers + + + +## Pre-review checklist for the PR author + +The PR author **must** check the checkboxes below when creating the PR. + +- [ ] I've confirmed the [contribution guidelines]. +- [ ] The PR follows the [pull request guidelines]. + +## In-review checklist for the PR reviewers + +The PR reviewers **must** check the checkboxes below before approval. + +- [ ] The PR follows the [pull request guidelines]. +- [ ] The PR has been properly tested. +- [ ] The PR has been reviewed by the code owners. + +## Post-review checklist for the PR author + +The PR author **must** check the checkboxes below before merging. + +- [ ] There are no open discussions or they are tracked via tickets. +- [ ] The PR is ready for merge. + +After all checkboxes are checked, anyone who has write access can merge the PR. + +[contribution guidelines]: https://autowarefoundation.github.io/autoware-documentation/main/contributing/ +[pull request guidelines]: https://autowarefoundation.github.io/autoware-documentation/main/contributing/pull-request-guidelines/ diff --git a/.github/stale.yml b/.github/stale.yml new file mode 100644 index 0000000000..84928d1b81 --- /dev/null +++ b/.github/stale.yml @@ -0,0 +1,12 @@ +# Modified from https://github.com/probot/stale#usage + +# Number of days of inactivity before an Issue or Pull Request with the stale label is closed +daysUntilClose: false + +# Label to use when marking as stale +staleLabel: stale + +# Comment to post when marking as stale +markComment: > + This pull request has been automatically marked as stale because it has not had + recent activity. diff --git a/CODE_OF_CONDUCT.md b/CODE_OF_CONDUCT.md new file mode 100644 index 0000000000..c493cad4da --- /dev/null +++ b/CODE_OF_CONDUCT.md @@ -0,0 +1,132 @@ +# Contributor Covenant Code of Conduct + +## Our Pledge + +We as members, contributors, and leaders pledge to make participation in our +community a harassment-free experience for everyone, regardless of age, body +size, visible or invisible disability, ethnicity, sex characteristics, gender +identity and expression, level of experience, education, socio-economic status, +nationality, personal appearance, race, caste, color, religion, or sexual +identity and orientation. + +We pledge to act and interact in ways that contribute to an open, welcoming, +diverse, inclusive, and healthy community. + +## Our Standards + +Examples of behavior that contributes to a positive environment for our +community include: + +- Demonstrating empathy and kindness toward other people +- Being respectful of differing opinions, viewpoints, and experiences +- Giving and gracefully accepting constructive feedback +- Accepting responsibility and apologizing to those affected by our mistakes, + and learning from the experience +- Focusing on what is best not just for us as individuals, but for the overall + community + +Examples of unacceptable behavior include: + +- The use of sexualized language or imagery, and sexual attention or advances of + any kind +- Trolling, insulting or derogatory comments, and personal or political attacks +- Public or private harassment +- Publishing others' private information, such as a physical or email address, + without their explicit permission +- Other conduct which could reasonably be considered inappropriate in a + professional setting + +## Enforcement Responsibilities + +Community leaders are responsible for clarifying and enforcing our standards of +acceptable behavior and will take appropriate and fair corrective action in +response to any behavior that they deem inappropriate, threatening, offensive, +or harmful. + +Community leaders have the right and responsibility to remove, edit, or reject +comments, commits, code, wiki edits, issues, and other contributions that are +not aligned to this Code of Conduct, and will communicate reasons for moderation +decisions when appropriate. + +## Scope + +This Code of Conduct applies within all community spaces, and also applies when +an individual is officially representing the community in public spaces. +Examples of representing our community include using an official e-mail address, +posting via an official social media account, or acting as an appointed +representative at an online or offline event. + +## Enforcement + +Instances of abusive, harassing, or otherwise unacceptable behavior may be +reported to the community leaders responsible for enforcement at +conduct@autoware.org. +All complaints will be reviewed and investigated promptly and fairly. + +All community leaders are obligated to respect the privacy and security of the +reporter of any incident. + +## Enforcement Guidelines + +Community leaders will follow these Community Impact Guidelines in determining +the consequences for any action they deem in violation of this Code of Conduct: + +### 1. Correction + +**Community Impact**: Use of inappropriate language or other behavior deemed +unprofessional or unwelcome in the community. + +**Consequence**: A private, written warning from community leaders, providing +clarity around the nature of the violation and an explanation of why the +behavior was inappropriate. A public apology may be requested. + +### 2. Warning + +**Community Impact**: A violation through a single incident or series of +actions. + +**Consequence**: A warning with consequences for continued behavior. No +interaction with the people involved, including unsolicited interaction with +those enforcing the Code of Conduct, for a specified period of time. This +includes avoiding interactions in community spaces as well as external channels +like social media. Violating these terms may lead to a temporary or permanent +ban. + +### 3. Temporary Ban + +**Community Impact**: A serious violation of community standards, including +sustained inappropriate behavior. + +**Consequence**: A temporary ban from any sort of interaction or public +communication with the community for a specified period of time. No public or +private interaction with the people involved, including unsolicited interaction +with those enforcing the Code of Conduct, is allowed during this period. +Violating these terms may lead to a permanent ban. + +### 4. Permanent Ban + +**Community Impact**: Demonstrating a pattern of violation of community +standards, including sustained inappropriate behavior, harassment of an +individual, or aggression toward or disparagement of classes of individuals. + +**Consequence**: A permanent ban from any sort of public interaction within the +community. + +## Attribution + +This Code of Conduct is adapted from the [Contributor Covenant][homepage], +version 2.1, available at +[https://www.contributor-covenant.org/version/2/1/code_of_conduct.html][v2.1]. + +Community Impact Guidelines were inspired by +[Mozilla's code of conduct enforcement ladder][mozilla coc]. + +For answers to common questions about this code of conduct, see the FAQ at +[https://www.contributor-covenant.org/faq][faq]. Translations are available at +[https://www.contributor-covenant.org/translations][translations]. + +[homepage]: https://www.contributor-covenant.org +[v2.1]: https://www.contributor-covenant.org/version/2/1/code_of_conduct.html +[mozilla coc]: https://github.com/mozilla/diversity +[faq]: https://www.contributor-covenant.org/faq +[translations]: https://www.contributor-covenant.org/translations diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md new file mode 100644 index 0000000000..22c7ee28e8 --- /dev/null +++ b/CONTRIBUTING.md @@ -0,0 +1,3 @@ +# Contributing + +See . diff --git a/DISCLAIMER.md b/DISCLAIMER.md new file mode 100644 index 0000000000..1b5a9bbe4d --- /dev/null +++ b/DISCLAIMER.md @@ -0,0 +1,46 @@ +DISCLAIMER + +“Autoware” will be provided by The Autoware Foundation under the Apache License 2.0. +This “DISCLAIMER” will be applied to all users of Autoware (a “User” or “Users”) with +the Apache License 2.0 and Users shall hereby approve and acknowledge all the contents +specified in this disclaimer below and will be deemed to consent to this +disclaimer without any objection upon utilizing or downloading Autoware. + +Disclaimer and Waiver of Warranties + +1. AUTOWARE FOUNDATION MAKES NO REPRESENTATION OR WARRANTY OF ANY KIND, + EXPRESS OR IMPLIED, WITH RESPECT TO PROVIDING AUTOWARE (the “Service”) + including but not limited to any representation or warranty (i) of fitness or + suitability for a particular purpose contemplated by the Users, (ii) of the + expected functions, commercial value, accuracy, or usefulness of the Service, + (iii) that the use by the Users of the Service complies with the laws and + regulations applicable to the Users or any internal rules established by + industrial organizations, (iv) that the Service will be free of interruption or + defects, (v) of the non-infringement of any third party's right and (vi) the + accuracy of the content of the Services and the software itself. + +2. The Autoware Foundation shall not be liable for any damage incurred by the + User that are attributable to the Autoware Foundation for any reasons + whatsoever. UNDER NO CIRCUMSTANCES SHALL THE AUTOWARE FOUNDATION BE LIABLE FOR + INCIDENTAL, INDIRECT, SPECIAL OR FUTURE DAMAGES OR LOSS OF PROFITS. + +3. A User shall be entirely responsible for the content posted by the User and + its use of any content of the Service or the Website. If the User is held + responsible in a civil action such as a claim for damages or even in a criminal + case, the Autoware Foundation and member companies, governments and academic & + non-profit organizations and their directors, officers, employees and agents + (collectively, the “Indemnified Parties”) shall be completely discharged from + any rights or assertions the User may have against the Indemnified Parties, or + from any legal action, litigation or similar procedures. + +Indemnity + +A User shall indemnify and hold the Indemnified Parties harmless from any of +their damages, losses, liabilities, costs or expenses (including attorneys' +fees or criminal compensation), or any claims or demands made against the +Indemnified Parties by any third party, due to or arising out of, or in +connection with utilizing Autoware (including the representations and +warranties), the violation of applicable Product Liability Law of each country +(including criminal case) or violation of any applicable laws by the Users, or +the content posted by the User or its use of any content of the Service or the +Website. From bae434ba462877b2717f6d4d25616a7f13260d6e Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Thu, 6 Apr 2023 11:01:21 +0900 Subject: [PATCH 809/851] fix(dispatch-release-note): dispatch workflow position (#31) fix: dispatch workflow position Signed-off-by: Shumpei Wakabayashi --- .github/{ => workflows}/dispatch-release-note.yaml | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename .github/{ => workflows}/dispatch-release-note.yaml (100%) diff --git a/.github/dispatch-release-note.yaml b/.github/workflows/dispatch-release-note.yaml similarity index 100% rename from .github/dispatch-release-note.yaml rename to .github/workflows/dispatch-release-note.yaml From 3668cd1c4ffb8b85c6b81cbc64b0d49b9267ba19 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Thu, 6 Apr 2023 16:10:06 +0900 Subject: [PATCH 810/851] ci(dispatch-release-note): dispatch beta branch and tag (#32) ci(dispatch-release-note): dispatch beta branch and tag Signed-off-by: Shumpei Wakabayashi --- .github/workflows/dispatch-release-note.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.github/workflows/dispatch-release-note.yaml b/.github/workflows/dispatch-release-note.yaml index 6b5d3df78a..792d46a8b2 100644 --- a/.github/workflows/dispatch-release-note.yaml +++ b/.github/workflows/dispatch-release-note.yaml @@ -2,7 +2,10 @@ name: dispatch-release-note on: push: branches: + - beta/v* - tier4/main + tags: + - v* workflow_dispatch: inputs: beta-branch-or-tag-name: From 0a3658ee5968223b33c8d6b5089eb7d241c17395 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Wed, 12 Apr 2023 10:48:25 +0900 Subject: [PATCH 811/851] ci: change awf sync trigger time (#45) --- .github/workflows/sync-awf-upstream.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/sync-awf-upstream.yaml b/.github/workflows/sync-awf-upstream.yaml index d2ee862fd4..c71bdef821 100644 --- a/.github/workflows/sync-awf-upstream.yaml +++ b/.github/workflows/sync-awf-upstream.yaml @@ -2,7 +2,7 @@ name: sync-awf-upstream on: schedule: - - cron: 0 0 * * * + - cron: 0 6 * * * workflow_dispatch: jobs: From 1ce1310a9169afcffa85edd4ec0bfe242e628554 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sat, 15 Apr 2023 00:16:09 +0000 Subject: [PATCH 812/851] chore: sync files (#52) Signed-off-by: GitHub Co-authored-by: shmpwk --- .pre-commit-config-optional.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.pre-commit-config-optional.yaml b/.pre-commit-config-optional.yaml index e0019e10d5..eb008730c1 100644 --- a/.pre-commit-config-optional.yaml +++ b/.pre-commit-config-optional.yaml @@ -1,6 +1,6 @@ repos: - repo: https://github.com/tcort/markdown-link-check - rev: v3.10.3 + rev: v3.11.1 hooks: - id: markdown-link-check - args: [--config=.markdown-link-check.json] + args: [--quiet, --config=.markdown-link-check.json] From 74fb7b8b64a00b5e0b1579d66f761f8a4ae580f0 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Sat, 15 Apr 2023 10:16:44 +0900 Subject: [PATCH 813/851] ci: cron weekdays except holidays (#51) * ci: cron week days * style(pre-commit): autofix --------- Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .github/workflows/sync-awf-upstream.yaml | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/.github/workflows/sync-awf-upstream.yaml b/.github/workflows/sync-awf-upstream.yaml index c71bdef821..6b288c64a5 100644 --- a/.github/workflows/sync-awf-upstream.yaml +++ b/.github/workflows/sync-awf-upstream.yaml @@ -2,7 +2,7 @@ name: sync-awf-upstream on: schedule: - - cron: 0 6 * * * + - cron: 0 6 * * 1-5 workflow_dispatch: jobs: @@ -16,8 +16,22 @@ jobs: app_id: ${{ secrets.APP_ID }} private_key: ${{ secrets.PRIVATE_KEY }} + - uses: actions/setup-node@v3 + with: + node-version: 16 + + - run: npm install @holiday-jp/holiday_jp + + - uses: actions/github-script@v6 + id: is-holiday + with: + script: | + const holiday_jp = require(`${process.env.GITHUB_WORKSPACE}/node_modules/@holiday-jp/holiday_jp`) + core.setOutput('holiday', holiday_jp.isHoliday(new Date())); + - name: Run sync-branches uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + if: ${{ steps.is-holiday.outputs.holiday != 'true' || github.event_name = 'workflow_dispatch' }} with: token: ${{ steps.generate-token.outputs.token }} base-branch: tier4/main From 0f8381dc7e9cb7027b06aedeea8eb0ff435017ac Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Mon, 17 Apr 2023 09:27:08 +0900 Subject: [PATCH 814/851] ci(sync-awf-upstream): fix failing CI (#53) ci: fix unexpected symbol: '=' --- .github/workflows/sync-awf-upstream.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/sync-awf-upstream.yaml b/.github/workflows/sync-awf-upstream.yaml index 6b288c64a5..03fd99c345 100644 --- a/.github/workflows/sync-awf-upstream.yaml +++ b/.github/workflows/sync-awf-upstream.yaml @@ -31,7 +31,7 @@ jobs: - name: Run sync-branches uses: autowarefoundation/autoware-github-actions/sync-branches@v1 - if: ${{ steps.is-holiday.outputs.holiday != 'true' || github.event_name = 'workflow_dispatch' }} + if: ${{ steps.is-holiday.outputs.holiday != 'true' || github.event_name == 'workflow_dispatch' }} with: token: ${{ steps.generate-token.outputs.token }} base-branch: tier4/main From e0909557093e2689cd725c718ecb06ed738b74fc Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Tue, 18 Apr 2023 19:48:10 +0900 Subject: [PATCH 815/851] ci(sync-awf-upstream): change awf sync time (#56) ci: change awf sync time --- .github/workflows/sync-awf-upstream.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/sync-awf-upstream.yaml b/.github/workflows/sync-awf-upstream.yaml index 03fd99c345..f0e6272286 100644 --- a/.github/workflows/sync-awf-upstream.yaml +++ b/.github/workflows/sync-awf-upstream.yaml @@ -2,7 +2,7 @@ name: sync-awf-upstream on: schedule: - - cron: 0 6 * * 1-5 + - cron: 0 1 * * 1-5 workflow_dispatch: jobs: From 68a026ecb8d4b1879a5653f551bd46c9f9589eb2 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sat, 13 May 2023 00:15:33 +0000 Subject: [PATCH 816/851] chore: sync files (#122) Signed-off-by: GitHub Co-authored-by: shmpwk --- .pre-commit-config-optional.yaml | 2 +- CODE_OF_CONDUCT.md | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.pre-commit-config-optional.yaml b/.pre-commit-config-optional.yaml index eb008730c1..3b43f9ae11 100644 --- a/.pre-commit-config-optional.yaml +++ b/.pre-commit-config-optional.yaml @@ -1,6 +1,6 @@ repos: - repo: https://github.com/tcort/markdown-link-check - rev: v3.11.1 + rev: v3.11.2 hooks: - id: markdown-link-check args: [--quiet, --config=.markdown-link-check.json] diff --git a/CODE_OF_CONDUCT.md b/CODE_OF_CONDUCT.md index c493cad4da..8dbcfb8510 100644 --- a/CODE_OF_CONDUCT.md +++ b/CODE_OF_CONDUCT.md @@ -60,7 +60,7 @@ representative at an online or offline event. Instances of abusive, harassing, or otherwise unacceptable behavior may be reported to the community leaders responsible for enforcement at -conduct@autoware.org. +. All complaints will be reviewed and investigated promptly and fairly. All community leaders are obligated to respect the privacy and security of the From 34ce1e2b1709f13b1c3a5e40373ca0b85746efde Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Tue, 23 May 2023 20:23:42 +0900 Subject: [PATCH 817/851] ci(dispatch-release-note): trigger by action_repository name (#150) feat(dispatch-release-note): trigger by action_repository name --- .github/workflows/dispatch-release-note.yaml | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/.github/workflows/dispatch-release-note.yaml b/.github/workflows/dispatch-release-note.yaml index 792d46a8b2..89356b6abd 100644 --- a/.github/workflows/dispatch-release-note.yaml +++ b/.github/workflows/dispatch-release-note.yaml @@ -17,16 +17,15 @@ jobs: runs-on: ubuntu-latest name: release-repository-dispatch steps: - - name: Set tag name - id: set-tag-name + - name: Set ref name + id: set-ref-name run: | if [ "${{ github.event_name }}" = "workflow_dispatch" ]; then REF_NAME="${{ github.event.inputs.beta-branch-or-tag-name }}" else REF_NAME="${{ github.ref_name }}" fi - echo ::set-output name=ref-name::"'$REF_NAME'_launch" - echo ::set-output name=tag-name::"${REF_NAME#beta/}" + echo ::set-output name=ref-name::"${{ github.repository }}/'$REF_NAME'" - name: Generate token id: generate-token uses: tibdex/github-app-token@v1 @@ -42,4 +41,4 @@ jobs: -H "Authorization: token ${{ steps.generate-token.outputs.token }}" \ -H "X-GitHub-Api-Version: 2022-11-28" \ "https://api.github.com/repos/tier4/update-release-notes/dispatches" \ - -d '{"event_type":"${{ steps.set-tag-name.outputs.ref-name }}"}' + -d '{"event_type":"${{ steps.set-ref-name.outputs.ref-name }}"}' From 17b1ff68c45295a7db9c895ef9c561770559d748 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 13 Jun 2023 00:20:35 +0000 Subject: [PATCH 818/851] chore: sync files (#181) Signed-off-by: GitHub Co-authored-by: shmpwk --- .github/workflows/pre-commit-optional.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.github/workflows/pre-commit-optional.yaml b/.github/workflows/pre-commit-optional.yaml index 93e05dc2c7..e754ecab24 100644 --- a/.github/workflows/pre-commit-optional.yaml +++ b/.github/workflows/pre-commit-optional.yaml @@ -9,8 +9,11 @@ jobs: steps: - name: Check out repository uses: actions/checkout@v3 + with: + fetch-depth: 0 - name: Run pre-commit uses: autowarefoundation/autoware-github-actions/pre-commit@v1 with: pre-commit-config: .pre-commit-config-optional.yaml + base-branch: origin/${{ github.base_ref }} From de6c6f08af6f2d7debe487140e4ab73a67c2db4c Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sat, 8 Jul 2023 00:19:15 +0000 Subject: [PATCH 819/851] chore: sync files (#200) Signed-off-by: GitHub Co-authored-by: shmpwk --- .github/workflows/build-and-test.yaml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 6459a98044..80d29409bc 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -24,6 +24,11 @@ jobs: - name: Check out repository uses: actions/checkout@v3 + - name: Free disk space (Ubuntu) + uses: jlumbroso/free-disk-space@v1.2.0 + with: + tool-cache: false + - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 From 1df3b119452fa843316e69d75c7bf4818f1c3328 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Tue, 11 Jul 2023 00:19:16 +0000 Subject: [PATCH 820/851] chore: sync files (#202) Signed-off-by: GitHub Co-authored-by: shmpwk --- .github/workflows/build-and-test.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 80d29409bc..33096b753d 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -28,6 +28,9 @@ jobs: uses: jlumbroso/free-disk-space@v1.2.0 with: tool-cache: false + dotnet: false + swap-storage: false + large-packages: false - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 From 360ef0f11965ac3140f6b854969bc2ee4b3a9eed Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Tue, 12 Sep 2023 15:23:34 +0900 Subject: [PATCH 821/851] chore: update sync upstream script (#236) Signed-off-by: tomoya.kimura --- .github/workflows/sync-awf-upstream.yaml | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/.github/workflows/sync-awf-upstream.yaml b/.github/workflows/sync-awf-upstream.yaml index f0e6272286..91012439fb 100644 --- a/.github/workflows/sync-awf-upstream.yaml +++ b/.github/workflows/sync-awf-upstream.yaml @@ -1,9 +1,12 @@ name: sync-awf-upstream on: - schedule: - - cron: 0 1 * * 1-5 workflow_dispatch: + inputs: + target_branch: + description: Target branch + required: true + type: string jobs: sync-awf-upstream: @@ -29,12 +32,17 @@ jobs: const holiday_jp = require(`${process.env.GITHUB_WORKSPACE}/node_modules/@holiday-jp/holiday_jp`) core.setOutput('holiday', holiday_jp.isHoliday(new Date())); + - name: Print warning for invalid branch name + if: ${{ inputs.target_branch == 'tier4/main' }} + run: | + echo This action cannot be performed on 'tier4/main' branch + - name: Run sync-branches uses: autowarefoundation/autoware-github-actions/sync-branches@v1 - if: ${{ steps.is-holiday.outputs.holiday != 'true' || github.event_name == 'workflow_dispatch' }} + if: ${{ inputs.target_branch != 'tier4/main' }} with: token: ${{ steps.generate-token.outputs.token }} - base-branch: tier4/main + base-branch: ${{ inputs.target_branch }} sync-pr-branch: sync-awf-upstream sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git sync-target-branch: main From 9877b916c67f5f3d4b13c98b38869e50132918ca Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Tue, 12 Sep 2023 15:23:45 +0900 Subject: [PATCH 822/851] chore: add workflow to merge beta branch to tier4 main (#239) * chore: add workflow to merge beta branch to tier4 main Signed-off-by: tomoya.kimura * fix: fix workflow name Signed-off-by: tomoya.kimura * fix: fix job name and pr-label Signed-off-by: tomoya.kimura * fix: fix variable name Signed-off-by: tomoya.kimura --------- Signed-off-by: tomoya.kimura --- .../workflows/beta-to-tier4-main-sync.yaml | 34 +++++++++++++++++++ 1 file changed, 34 insertions(+) create mode 100644 .github/workflows/beta-to-tier4-main-sync.yaml diff --git a/.github/workflows/beta-to-tier4-main-sync.yaml b/.github/workflows/beta-to-tier4-main-sync.yaml new file mode 100644 index 0000000000..79bdb6f0bd --- /dev/null +++ b/.github/workflows/beta-to-tier4-main-sync.yaml @@ -0,0 +1,34 @@ +name: beta-to-tier4-main-sync + +on: + workflow_dispatch: + inputs: + source_branch: + description: Source branch + required: true + type: string + +jobs: + sync-beta-branch: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + base-branch: tier4/main + sync-pr-branch: beta-to-tier4-main-sync + sync-target-repository: https://github.com/tier4/autoware_launch.git + sync-target-branch: ${{ inputs.source_branch }} + pr-title: "chore: sync beta branch ${{ inputs.source_branch }} with tier4/main" + pr-labels: | + bot + sync-beta-branch + auto-merge-method: merge From 2193bdc3e0fc631a86044580f9d0e2df3a2e457f Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sat, 4 Nov 2023 00:15:42 +0000 Subject: [PATCH 823/851] chore: sync files (#251) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/dependabot.yaml | 4 ++-- .github/workflows/sync-files.yaml | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/dependabot.yaml b/.github/dependabot.yaml index 3f3bf243f6..0264c03535 100644 --- a/.github/dependabot.yaml +++ b/.github/dependabot.yaml @@ -6,5 +6,5 @@ updates: interval: daily open-pull-requests-limit: 1 labels: - - bot - - github-actions + - tag:bot + - type:github-actions diff --git a/.github/workflows/sync-files.yaml b/.github/workflows/sync-files.yaml index b9dc5907a5..5025e6c8bd 100644 --- a/.github/workflows/sync-files.yaml +++ b/.github/workflows/sync-files.yaml @@ -28,6 +28,6 @@ jobs: with: token: ${{ steps.generate-token.outputs.token }} pr-labels: | - bot - sync-files + tag:bot + tag:sync-files auto-merge-method: squash From 03e7b04470f92a70245b27ede32ef5f9df7506d6 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Thu, 16 Nov 2023 00:16:45 +0000 Subject: [PATCH 824/851] chore: sync files (#255) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/stale.yml | 2 +- .github/workflows/cancel-previous-workflows.yaml | 2 +- .github/workflows/github-release.yaml | 2 +- .github/workflows/pre-commit-optional.yaml | 2 +- .github/workflows/pre-commit.yaml | 2 +- .github/workflows/spell-check-differential.yaml | 2 +- 6 files changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/stale.yml b/.github/stale.yml index 84928d1b81..bc99e4383c 100644 --- a/.github/stale.yml +++ b/.github/stale.yml @@ -4,7 +4,7 @@ daysUntilClose: false # Label to use when marking as stale -staleLabel: stale +staleLabel: status:stale # Comment to post when marking as stale markComment: > diff --git a/.github/workflows/cancel-previous-workflows.yaml b/.github/workflows/cancel-previous-workflows.yaml index f9c29b81b6..1da4d24966 100644 --- a/.github/workflows/cancel-previous-workflows.yaml +++ b/.github/workflows/cancel-previous-workflows.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Cancel previous runs - uses: styfle/cancel-workflow-action@0.11.0 + uses: styfle/cancel-workflow-action@0.12.0 with: workflow_id: all all_but_latest: true diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 95ebb8725f..b426d0cba6 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -30,7 +30,7 @@ jobs: echo "tag-name=${REF_NAME#beta/}" >> $GITHUB_OUTPUT - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 ref: ${{ steps.set-tag-name.outputs.ref-name }} diff --git a/.github/workflows/pre-commit-optional.yaml b/.github/workflows/pre-commit-optional.yaml index e754ecab24..38738196a0 100644 --- a/.github/workflows/pre-commit-optional.yaml +++ b/.github/workflows/pre-commit-optional.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml index b231dbda87..33c00ee106 100644 --- a/.github/workflows/pre-commit.yaml +++ b/.github/workflows/pre-commit.yaml @@ -16,7 +16,7 @@ jobs: private_key: ${{ secrets.PRIVATE_KEY }} - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: ref: ${{ github.event.pull_request.head.ref }} diff --git a/.github/workflows/spell-check-differential.yaml b/.github/workflows/spell-check-differential.yaml index eb18ccdba3..1fbf2ff469 100644 --- a/.github/workflows/spell-check-differential.yaml +++ b/.github/workflows/spell-check-differential.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Run spell-check uses: autowarefoundation/autoware-github-actions/spell-check@v1 From 528143215a53f4501932d32e18161b80d6f38a90 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 7 Dec 2023 01:04:46 +0900 Subject: [PATCH 825/851] feat(start_planner): add surround moving obstacle check (#723) update start_planner.param.yaml Signed-off-by: kyoichi-sugahara --- .../start_planner/start_planner.param.yaml | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml index 420d9b5fcc..514d61e225 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml @@ -84,7 +84,6 @@ ego_predicted_path: min_velocity: 0.0 min_acceleration: 1.0 - max_velocity: 1.0 time_horizon_for_front_object: 10.0 time_horizon_for_rear_object: 10.0 time_resolution: 0.5 @@ -139,6 +138,20 @@ backward_path_length: 30.0 forward_path_length: 100.0 + surround_moving_obstacle_check: + search_radius: 10.0 + th_moving_obstacle_velocity: 1.0 + # ObjectTypesToCheck + object_types_to_check: + check_car: true + check_truck: true + check_bus: true + check_trailer: true + check_bicycle: true + check_motorcycle: true + check_pedestrian: true + check_unknown: false + # debug debug: print_debug_info: false From eb1cc8c933d9d18dbfb079edc8cebee5464e7157 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 28 Dec 2023 01:42:50 +0900 Subject: [PATCH 826/851] feat: add github workflow of create-awf-latest.yml Signed-off-by: Takayuki Murooka --- .github/workflows/create-awf-latest.yml | 25 +++++++++++++++++++++++++ 1 file changed, 25 insertions(+) create mode 100644 .github/workflows/create-awf-latest.yml diff --git a/.github/workflows/create-awf-latest.yml b/.github/workflows/create-awf-latest.yml new file mode 100644 index 0000000000..d68a6c3cb5 --- /dev/null +++ b/.github/workflows/create-awf-latest.yml @@ -0,0 +1,25 @@ +name: create-awf-latest + +on: + schedule: + - cron: 0 0 * * * + workflow_dispatch: + +jobs: + create-awf-latest: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v2 + with: + fetch-depth: 0 + - name: Commit Results + run: | + git config --local user.email "action@github.com" + git config --local user.name "GitHub Action" + + git checkout awf-latest + git remote add awf https://github.com/autowarefoundation/autoware_launch + git fetch awf main + git rebase awf/main + + git push origin awf-latest --force From 595d4402d7f58ecb16fac956bd08ae76801ee755 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 10 Jan 2024 10:40:08 +0900 Subject: [PATCH 827/851] fix(pointpainting): update parameter structure (#778) * fix(pointpainting): update parameter structure Signed-off-by: kminoda * update roi_sync.param.yaml Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../roi_sync.param.yaml | 2 + .../lidar_model/pointpainting.param.yaml | 40 +++++++++++-------- 2 files changed, 26 insertions(+), 16 deletions(-) diff --git a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml index 0e4c52ba92..99d85089be 100644 --- a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml +++ b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml @@ -3,6 +3,8 @@ input_offset_ms: [61.67, 111.67, 45.0, 28.33, 78.33, 95.0] timeout_ms: 70.0 match_threshold_ms: 50.0 + image_buffer_size: 15 + debug_mode: false filter_scope_min_x: -100.0 filter_scope_min_y: -100.0 filter_scope_min_z: -100.0 diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml index e1be5426cb..21d31f2163 100755 --- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml +++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml @@ -1,18 +1,26 @@ /**: ros__parameters: - class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] - paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] - point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle - max_voxel_size: 40000 - point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] - voxel_size: [0.32, 0.32, 8.0] - downsample_factor: 1 - encoder_in_feature_size: 12 - yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] - # post-process params - circle_nms_dist_threshold: 0.3 - iou_nms_target_class_names: ["CAR"] - iou_nms_search_distance_2d: 10.0 - iou_nms_threshold: 0.1 - # omp params - omp_num_threads: 1 + model_params: + class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] + paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] + point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle + max_voxel_size: 40000 + point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] + voxel_size: [0.32, 0.32, 8.0] + downsample_factor: 1 + encoder_in_feature_size: 12 + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] + has_twist: false + densification_params: + world_frame_id: "map" + num_past_frames: 0 + post_process_params: + # post-process params + circle_nms_dist_threshold: 0.3 + iou_nms_target_class_names: ["CAR"] + iou_nms_search_distance_2d: 10.0 + iou_nms_threshold: 0.1 + score_threshold: 0.4 + omp_params: + # omp params + num_threads: 1 From 9f2da38695ddd1e0e7ada003e74218b643a10e88 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 10 Jan 2024 11:49:53 +0900 Subject: [PATCH 828/851] fix(rviz): hide traffic light regulatory element id (#777) Signed-off-by: satoshi-ota --- autoware_launch/rviz/autoware.rviz | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index bc22eadb70..7aac371ce9 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -397,6 +397,7 @@ Visualization Manager: shoulder_road_lanelets: false traffic_light: true traffic_light_id: false + traffic_light_reg_elem_id: false traffic_light_triangle: true walkway_lanelets: true hatched_road_markings_bound: true From 69f92e1e6e6186a6ff49f1af68df5e50cd04988d Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 11 Jan 2024 10:37:32 +0900 Subject: [PATCH 829/851] feat(behavior_velocity_planner): add new 'dynamic_obstacle_stop' module (#267) feat(behavior_velocity_planner): add new 'dynamic_obstacle_stop' module (#730) Signed-off-by: Maxime CLEMENT --- .../planning/preset/default_preset.yaml | 3 +++ .../dynamic_obstacle_stop.param.yaml | 10 ++++++++ .../tier4_planning_component.launch.xml | 1 + autoware_launch/rviz/autoware.rviz | 24 +++++++++++++++++++ 4 files changed, 38 insertions(+) create mode 100644 autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml index 7bd3dd26b3..3df13a108d 100644 --- a/autoware_launch/config/planning/preset/default_preset.yaml +++ b/autoware_launch/config/planning/preset/default_preset.yaml @@ -77,6 +77,9 @@ launch: - arg: name: launch_no_drivable_lane_module default: "false" + - arg: + name: launch_dynamic_obstacle_stop_module + default: "true" # motion planning modules - arg: diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml new file mode 100644 index 0000000000..14483093e8 --- /dev/null +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml @@ -0,0 +1,10 @@ +/**: + ros__parameters: + dynamic_obstacle_stop: # module to stop or before entering the immediate path of a moving object + extra_object_width: 1.0 # [m] extra width around detected objects + minimum_object_velocity: 0.5 # [m/s] objects with a velocity bellow this value are ignored + stop_distance_buffer: 0.5 # [m] extra distance to add between the stop point and the collision point + time_horizon: 5.0 # [s] time horizon used for collision checks + hysteresis: 1.0 # [m] once a collision has been detected, this hysteresis is used on the collision detection + decision_duration_buffer : 1.0 # [s] duration between no collision being detected and the stop decision being cancelled + minimum_object_distance_from_ego_path: 1.0 # [m] minimum distance between the footprints of ego and an object to consider for collision diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml index 5fb17541cd..3e9061da80 100644 --- a/autoware_launch/launch/components/tier4_planning_component.launch.xml +++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml @@ -49,6 +49,7 @@ + diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 7aac371ce9..a0ade56821 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1677,6 +1677,18 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/no_drivable_lane Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (DynamicObstacleStop) + 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/virtual_wall/dynamic_obstacle_stop + Value: true Enabled: true Name: VirtualWall - Class: rviz_common/Group @@ -1945,6 +1957,18 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_drivable_lane Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: DynamicObstacleStop + 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/dynamic_obstacle_stop + Value: false Enabled: false Name: DebugMarker - Class: rviz_common/Group From 63b3131910631b303095e045e79f3a90ff978e04 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 11 Jan 2024 11:38:33 +0900 Subject: [PATCH 830/851] feat(start_planner): keep distance against front objects (#766) Add collision check margin from front object Signed-off-by: kyoichi-sugahara --- .../behavior_path_planner/start_planner/start_planner.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml index 514d61e225..d04728861a 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml @@ -7,6 +7,7 @@ th_stopped_time: 1.0 collision_check_margin: 1.0 collision_check_distance_from_end: 1.0 + collision_check_margin_from_front_object: 5.0 th_moving_object_velocity: 1.0 th_distance_to_middle_of_the_road: 0.5 center_line_path_interval: 1.0 From 57524f1f2f6513a4dbf665430f6ba6b92fa77f78 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 11 Jan 2024 14:54:25 +0900 Subject: [PATCH 831/851] feat(start_planner): define collision check margin as list (#770) * Update collision check margins in start planner configuration Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../start_planner/start_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml index d04728861a..277771f13f 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml @@ -5,7 +5,7 @@ th_arrived_distance: 1.0 th_stopped_velocity: 0.01 th_stopped_time: 1.0 - collision_check_margin: 1.0 + collision_check_margins: [2.0, 1.0, 0.5, 0.1] collision_check_distance_from_end: 1.0 collision_check_margin_from_front_object: 5.0 th_moving_object_velocity: 1.0 From 6671c444077cce03be725ba9d3bfebd578fda901 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 11 Jan 2024 18:35:23 +0900 Subject: [PATCH 832/851] fix(intersection): fix bugs (#781) Signed-off-by: Mamoru Sobue --- .../behavior_velocity_planner/intersection.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index 6fc136c512..4e9eb50f2a 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -72,7 +72,7 @@ enable: false creep_velocity: 0.8333 peeking_offset: -0.5 - occlusion_required_clearance_distance: 55 + occlusion_required_clearance_distance: 55.0 possible_object_bbox: [1.5, 2.5] ignore_parked_vehicle_speed_threshold: 0.8333 occlusion_detection_hold_time: 1.5 From b5e63b726ea942c3a8e77d49ecb5448841e16a8c Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 12 Jan 2024 21:03:28 +0900 Subject: [PATCH 833/851] feat(multi_object_tracker): fix typo in param name and change default value (#271) feat(multi_object_tracker): fix typo in param name and change default value (#785) * fix(multi_object_tracker): fix typo in param name * feat: update default param --------- Signed-off-by: kminoda --- .../multi_object_tracker_node.param.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/multi_object_tracker_node.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/multi_object_tracker_node.param.yaml index f58de8e615..32a12f8bf5 100644 --- a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/multi_object_tracker_node.param.yaml +++ b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/multi_object_tracker_node.param.yaml @@ -17,7 +17,7 @@ publish_untracked_objects: false # debug parameters - publish_processing_time: false + publish_processing_time: true publish_tentative_objects: false - diagnostic_warn_delay: 0.5 # [sec] - diagnostic_error_delay: 1.0 # [sec] + diagnostics_warn_delay: 0.5 # [sec] + diagnostics_error_delay: 1.0 # [sec] From 6188c02da6b1ef34e579ceb6e7035d9d56581c49 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 15 Jan 2024 00:28:14 +0900 Subject: [PATCH 834/851] feat: add sync-awf-latest.yaml (#272) Signed-off-by: Takayuki Murooka --- .github/workflows/sync-awf-latest.yaml | 30 ++++++++++++++++++++++++++ 1 file changed, 30 insertions(+) create mode 100644 .github/workflows/sync-awf-latest.yaml diff --git a/.github/workflows/sync-awf-latest.yaml b/.github/workflows/sync-awf-latest.yaml new file mode 100644 index 0000000000..ba1380ddac --- /dev/null +++ b/.github/workflows/sync-awf-latest.yaml @@ -0,0 +1,30 @@ +name: sync-awf-latest + +on: + schedule: + - cron: 0 15 * * * + workflow_dispatch: + +jobs: + sync-awf-latest: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + base-branch: awf-latest + sync-pr-branch: sync-awf-latest + sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git + sync-target-branch: main + pr-title: "chore: sync awf-latest" + pr-labels: | + bot + auto-merge-method: merge From ebe27ff31fb405f181345bcd28baf284797c7f86 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 15 Jan 2024 00:37:14 +0900 Subject: [PATCH 835/851] chore: disable auto-merge of sync-awf-latest (#274) Signed-off-by: Takayuki Murooka --- .github/workflows/sync-awf-latest.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/.github/workflows/sync-awf-latest.yaml b/.github/workflows/sync-awf-latest.yaml index ba1380ddac..69188341d2 100644 --- a/.github/workflows/sync-awf-latest.yaml +++ b/.github/workflows/sync-awf-latest.yaml @@ -27,4 +27,3 @@ jobs: pr-title: "chore: sync awf-latest" pr-labels: | bot - auto-merge-method: merge From a66612014065fdffddb479aa4a88a02a3e4a797d Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Mon, 15 Jan 2024 14:25:40 +0900 Subject: [PATCH 836/851] feat(start_planner): shorten max backward distance (#734) Update start_planner.param.yaml --- .../start_planner/start_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml index 277771f13f..592302ce5d 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml @@ -32,7 +32,7 @@ # search start pose backward enable_back: true search_priority: "efficient_path" # "efficient_path" or "short_back_distance" - max_back_distance: 30.0 + max_back_distance: 20.0 backward_search_resolution: 2.0 backward_path_update_duration: 3.0 ignore_distance_from_lane_end: 15.0 From 4e175efb0cc095334bcd6a11129b3f9d4656be1b Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 18 Jan 2024 11:07:55 +0900 Subject: [PATCH 837/851] feat: enable auto-merge in sync-awf-latest.yaml Signed-off-by: Takayuki Murooka --- .github/workflows/sync-awf-latest.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/sync-awf-latest.yaml b/.github/workflows/sync-awf-latest.yaml index 69188341d2..ba1380ddac 100644 --- a/.github/workflows/sync-awf-latest.yaml +++ b/.github/workflows/sync-awf-latest.yaml @@ -27,3 +27,4 @@ jobs: pr-title: "chore: sync awf-latest" pr-labels: | bot + auto-merge-method: merge From 5d445fc24984a59a0b91a38fcca2ffe3c1655685 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Thu, 25 Jan 2024 00:17:17 +0000 Subject: [PATCH 838/851] chore: sync files (#291) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/workflows/build-and-test-differential.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 8eeb1de069..ad9fc6620e 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -74,7 +74,7 @@ jobs: - name: Get modified files id: get-modified-files - uses: tj-actions/changed-files@v35 + uses: tj-actions/changed-files@v42 with: files: | **/*.cpp From e1d07dc30bc07c365b562d62ee210e3e3801f7b1 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Fri, 2 Feb 2024 00:15:37 +0000 Subject: [PATCH 839/851] chore: sync files (#299) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/workflows/build-and-test.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 33096b753d..c34102cec0 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -25,7 +25,7 @@ jobs: uses: actions/checkout@v3 - name: Free disk space (Ubuntu) - uses: jlumbroso/free-disk-space@v1.2.0 + uses: jlumbroso/free-disk-space@v1.3.1 with: tool-cache: false dotnet: false From 43c1989bc85923e464898ca1ed89ee6b9292b15f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 7 Feb 2024 17:41:47 +0900 Subject: [PATCH 840/851] feat: use tier4/awf-latest for upstream sync Signed-off-by: Takayuki Murooka --- .github/workflows/sync-awf-upstream.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/sync-awf-upstream.yaml b/.github/workflows/sync-awf-upstream.yaml index 91012439fb..3a8dd05797 100644 --- a/.github/workflows/sync-awf-upstream.yaml +++ b/.github/workflows/sync-awf-upstream.yaml @@ -44,9 +44,9 @@ jobs: token: ${{ steps.generate-token.outputs.token }} base-branch: ${{ inputs.target_branch }} sync-pr-branch: sync-awf-upstream - sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git - sync-target-branch: main - pr-title: "chore: sync awf/autoware_launch" + sync-target-repository: https://github.com/tier4/autoware_launch.git + sync-target-branch: awf-latest + pr-title: "chore: sync tier4/autoware_launch:awf-latest" pr-labels: | bot sync-awf-upstream From d88b9d128cbbfd89e5cd3b4fb744784dc9d3723a Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Wed, 14 Feb 2024 00:16:26 +0000 Subject: [PATCH 841/851] chore: sync files (#315) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/workflows/backport.yaml | 2 +- .github/workflows/pre-commit.yaml | 2 +- .github/workflows/sync-files.yaml | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/backport.yaml b/.github/workflows/backport.yaml index 7a9d63f79c..d79e709888 100644 --- a/.github/workflows/backport.yaml +++ b/.github/workflows/backport.yaml @@ -22,7 +22,7 @@ jobs: steps: - name: Generate token id: generate-token - uses: tibdex/github-app-token@v1 + uses: tibdex/github-app-token@v2 with: app_id: ${{ secrets.APP_ID }} private_key: ${{ secrets.PRIVATE_KEY }} diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml index 33c00ee106..c724885fcb 100644 --- a/.github/workflows/pre-commit.yaml +++ b/.github/workflows/pre-commit.yaml @@ -10,7 +10,7 @@ jobs: steps: - name: Generate token id: generate-token - uses: tibdex/github-app-token@v1 + uses: tibdex/github-app-token@v2 with: app_id: ${{ secrets.APP_ID }} private_key: ${{ secrets.PRIVATE_KEY }} diff --git a/.github/workflows/sync-files.yaml b/.github/workflows/sync-files.yaml index 5025e6c8bd..51e523b803 100644 --- a/.github/workflows/sync-files.yaml +++ b/.github/workflows/sync-files.yaml @@ -18,7 +18,7 @@ jobs: steps: - name: Generate token id: generate-token - uses: tibdex/github-app-token@v1 + uses: tibdex/github-app-token@v2 with: app_id: ${{ secrets.APP_ID }} private_key: ${{ secrets.PRIVATE_KEY }} From a154e68e678c428db14f6c7ae30f0805ca35af39 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 29 Feb 2024 23:17:17 +0900 Subject: [PATCH 842/851] chore: remove unnecessary workflows Signed-off-by: Takayuki Murooka --- .github/workflows/create-awf-latest.yml | 25 ----------------- .github/workflows/sync-awf-latest-s1.yaml | 31 ---------------------- .github/workflows/sync-awf-latest-x1.yaml | 31 ---------------------- .github/workflows/sync-awf-latest-x2.yaml | 31 ---------------------- .github/workflows/sync-awf-latest-xx1.yaml | 31 ---------------------- .github/workflows/sync-tier4-upstream.yaml | 31 ---------------------- 6 files changed, 180 deletions(-) delete mode 100644 .github/workflows/create-awf-latest.yml delete mode 100644 .github/workflows/sync-awf-latest-s1.yaml delete mode 100644 .github/workflows/sync-awf-latest-x1.yaml delete mode 100644 .github/workflows/sync-awf-latest-x2.yaml delete mode 100644 .github/workflows/sync-awf-latest-xx1.yaml delete mode 100644 .github/workflows/sync-tier4-upstream.yaml diff --git a/.github/workflows/create-awf-latest.yml b/.github/workflows/create-awf-latest.yml deleted file mode 100644 index d68a6c3cb5..0000000000 --- a/.github/workflows/create-awf-latest.yml +++ /dev/null @@ -1,25 +0,0 @@ -name: create-awf-latest - -on: - schedule: - - cron: 0 0 * * * - workflow_dispatch: - -jobs: - create-awf-latest: - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v2 - with: - fetch-depth: 0 - - name: Commit Results - run: | - git config --local user.email "action@github.com" - git config --local user.name "GitHub Action" - - git checkout awf-latest - git remote add awf https://github.com/autowarefoundation/autoware_launch - git fetch awf main - git rebase awf/main - - git push origin awf-latest --force diff --git a/.github/workflows/sync-awf-latest-s1.yaml b/.github/workflows/sync-awf-latest-s1.yaml deleted file mode 100644 index c14d001c61..0000000000 --- a/.github/workflows/sync-awf-latest-s1.yaml +++ /dev/null @@ -1,31 +0,0 @@ -name: sync-awf-latest-s1 - -on: - schedule: - - cron: 0 0 * * * - workflow_dispatch: - -jobs: - sync-awf-latest-s1: - runs-on: ubuntu-latest - steps: - - name: Generate token - id: generate-token - uses: tibdex/github-app-token@v1 - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.PRIVATE_KEY }} - - - name: Run sync-branches - uses: autowarefoundation/autoware-github-actions/sync-branches@v1 - with: - token: ${{ steps.generate-token.outputs.token }} - base-branch: awf-latest-s1 - sync-pr-branch: sync-awf-latest-s1 - sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git - sync-target-branch: main - pr-title: "chore: sync awf-latest-s1" - pr-labels: | - bot - sync-awf-latest-s1 - auto-merge-method: merge diff --git a/.github/workflows/sync-awf-latest-x1.yaml b/.github/workflows/sync-awf-latest-x1.yaml deleted file mode 100644 index c348e6d853..0000000000 --- a/.github/workflows/sync-awf-latest-x1.yaml +++ /dev/null @@ -1,31 +0,0 @@ -name: sync-awf-latest-x1 - -on: - schedule: - - cron: 0 0 * * * - workflow_dispatch: - -jobs: - sync-awf-latest-x1: - runs-on: ubuntu-latest - steps: - - name: Generate token - id: generate-token - uses: tibdex/github-app-token@v1 - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.PRIVATE_KEY }} - - - name: Run sync-branches - uses: autowarefoundation/autoware-github-actions/sync-branches@v1 - with: - token: ${{ steps.generate-token.outputs.token }} - base-branch: awf-latest-x1 - sync-pr-branch: sync-awf-latest-x1 - sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git - sync-target-branch: main - pr-title: "chore: sync awf-latest-x1" - pr-labels: | - bot - sync-awf-latest-x1 - auto-merge-method: merge diff --git a/.github/workflows/sync-awf-latest-x2.yaml b/.github/workflows/sync-awf-latest-x2.yaml deleted file mode 100644 index 97ed22a5f7..0000000000 --- a/.github/workflows/sync-awf-latest-x2.yaml +++ /dev/null @@ -1,31 +0,0 @@ -name: sync-awf-latest-x2 - -on: - schedule: - - cron: 0 0 * * * - workflow_dispatch: - -jobs: - sync-awf-latest-x2: - runs-on: ubuntu-latest - steps: - - name: Generate token - id: generate-token - uses: tibdex/github-app-token@v1 - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.PRIVATE_KEY }} - - - name: Run sync-branches - uses: autowarefoundation/autoware-github-actions/sync-branches@v1 - with: - token: ${{ steps.generate-token.outputs.token }} - base-branch: awf-latest-x2 - sync-pr-branch: sync-awf-latest-x2 - sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git - sync-target-branch: main - pr-title: "chore: sync awf-latest-x2" - pr-labels: | - bot - sync-awf-latest-x2 - auto-merge-method: merge diff --git a/.github/workflows/sync-awf-latest-xx1.yaml b/.github/workflows/sync-awf-latest-xx1.yaml deleted file mode 100644 index 6b6432b55e..0000000000 --- a/.github/workflows/sync-awf-latest-xx1.yaml +++ /dev/null @@ -1,31 +0,0 @@ -name: sync-awf-latest-xx1 - -on: - schedule: - - cron: 0 0 * * * - workflow_dispatch: - -jobs: - sync-awf-latest-xx1: - runs-on: ubuntu-latest - steps: - - name: Generate token - id: generate-token - uses: tibdex/github-app-token@v1 - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.PRIVATE_KEY }} - - - name: Run sync-branches - uses: autowarefoundation/autoware-github-actions/sync-branches@v1 - with: - token: ${{ steps.generate-token.outputs.token }} - base-branch: awf-latest-xx1 - sync-pr-branch: sync-awf-latest-xx1 - sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git - sync-target-branch: main - pr-title: "chore: sync awf-latest-xx1" - pr-labels: | - bot - sync-awf-latest-xx1 - auto-merge-method: merge diff --git a/.github/workflows/sync-tier4-upstream.yaml b/.github/workflows/sync-tier4-upstream.yaml deleted file mode 100644 index b7dc824f8a..0000000000 --- a/.github/workflows/sync-tier4-upstream.yaml +++ /dev/null @@ -1,31 +0,0 @@ -name: sync-tier4-upstream - -on: - schedule: - - cron: 0 0 * * * - workflow_dispatch: - -jobs: - sync-tier4-upstream: - runs-on: ubuntu-latest - steps: - - name: Generate token - id: generate-token - uses: tibdex/github-app-token@v1 - with: - app_id: ${{ secrets.APP_ID }} - private_key: ${{ secrets.PRIVATE_KEY }} - - - name: Run sync-branches - uses: autowarefoundation/autoware-github-actions/sync-branches@v1 - with: - token: ${{ steps.generate-token.outputs.token }} - base-branch: tier4/main - sync-pr-branch: sync-tier4-upstream - sync-target-repository: https://github.com/tier4/autoware_launch.git - sync-target-branch: tier4/main - pr-title: "chore: sync upstream" - pr-labels: | - bot - sync-tier4-upstream - auto-merge-method: merge From 6088c2a9db6b90593b9965d91170a18e8a9ae23e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 29 Feb 2024 23:29:10 +0900 Subject: [PATCH 843/851] fix Signed-off-by: Takayuki Murooka --- .github/workflows/sync-tier4-upstream.yaml | 32 ++++++++++++++++++++++ 1 file changed, 32 insertions(+) create mode 100644 .github/workflows/sync-tier4-upstream.yaml diff --git a/.github/workflows/sync-tier4-upstream.yaml b/.github/workflows/sync-tier4-upstream.yaml new file mode 100644 index 0000000000..b97a9bab28 --- /dev/null +++ b/.github/workflows/sync-tier4-upstream.yaml @@ -0,0 +1,32 @@ +# This workflow is intended for the use in the repositories created by forking tier4/autoware_launch. +name: sync-tier4-upstream + +on: + schedule: + - cron: 0 0 * * * + workflow_dispatch: + +jobs: + sync-tier4-upstream: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + base-branch: tier4/main + sync-pr-branch: sync-tier4-upstream + sync-target-repository: https://github.com/tier4/autoware_launch.git + sync-target-branch: tier4/main + pr-title: "chore: sync upstream" + pr-labels: | + bot + sync-tier4-upstream + auto-merge-method: merge From a4456a4111e1c8c82e3a5b0d8b0d215cedb2b277 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Sat, 9 Mar 2024 00:11:58 +0000 Subject: [PATCH 844/851] chore: update CODEOWNERS (#340) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index dd28f74253..b9d67e0b94 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -1,10 +1,10 @@ ### Automatically generated from package.xml ### -autoware_launch/** yukihiro.saito@tier4.jp +autoware_launch/** mfc@leodrive.ai ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp ### Copied from .github/CODEOWNERS-manual ### # /** # .github/** -autoware_launch/** yukihiro.saito@tier4.jp ryohsuke.mitsudome@tier4.jp +autoware_launch/** yukihiro.saito@tier4.jp ryohsuke.mitsudome@tier4.jp mfc@leodrive.ai autoware_launch/config/control/** takayuki.murooka@tier4.jp fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp autoware_launch/config/localization/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp ryu.yamamoto@tier4.jp kento.yabuuchi.2@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp anh.nguyen.2@tier4.jp autoware_launch/config/map/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp ryu.yamamoto@tier4.jp kento.yabuuchi.2@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp anh.nguyen.2@tier4.jp From 28382905efa737c688dba329bfd4f14b7dafcd7d Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Mon, 18 Mar 2024 15:56:29 +0900 Subject: [PATCH 845/851] feat(ci): add sync-tier4-upstream-up-to-tag (#347) * feat(ci): add sync-tier4-upstream-up-to-tag * style(pre-commit): autofix * delete quote --------- Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../sync-tier4-upstream-up-to-tag.yaml | 92 +++++++++++++++++++ 1 file changed, 92 insertions(+) create mode 100644 .github/workflows/sync-tier4-upstream-up-to-tag.yaml diff --git a/.github/workflows/sync-tier4-upstream-up-to-tag.yaml b/.github/workflows/sync-tier4-upstream-up-to-tag.yaml new file mode 100644 index 0000000000..f85b58a2fa --- /dev/null +++ b/.github/workflows/sync-tier4-upstream-up-to-tag.yaml @@ -0,0 +1,92 @@ +# This workflow is intended for the use in the repositories created by forking tier4/autoware_launch. +name: sync-tier4-upstream-up-to-tag + +on: + workflow_dispatch: + inputs: + sync-target-tag: + description: sync target tag like v0.24.0 + required: true + type: string + default: "" + +jobs: + sync-tier4-upstream-up-to-tag: + runs-on: ubuntu-latest + env: + BASE_BRANCH: tier4/main + SYNC_TARGET_REPOSITORY: https://github.com/tier4/autoware_launch.git + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Check out repository + uses: actions/checkout@v4 + with: + ref: ${{ env.BASE_BRANCH }} + fetch-depth: 0 + + - name: Set git config + uses: autowarefoundation/autoware-github-actions/set-git-config@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + + - name: Sync tag + run: | + git remote add sync-target ${{ env.SYNC_TARGET_REPOSITORY }} + git fetch -pPtf --all + git reset --hard "${{ inputs.sync-target-tag }}" + git remote rm sync-target + shell: bash + + - name: Generate changelog + id: generate-changelog + uses: autowarefoundation/autoware-github-actions/generate-changelog@v1 + with: + git-cliff-args: origin/${{ env.BASE_BRANCH }}..HEAD + + - name: Replace PR number to URL + id: replace-pr-number-to-url + run: | + # Output multiline strings: https://docs.github.com/en/actions/using-workflows/workflow-commands-for-github-actions#example-of-a-multiline-string + changelog=$(echo "$CHANGELOG" | sed -r "s|\(#([0-9]+)\)|("${REPO_URL%.git}"/pull/\1)|g") + EOF=$(dd if=/dev/urandom bs=15 count=1 status=none | base64) + echo "changelog<<$EOF" >> $GITHUB_OUTPUT + echo "$changelog" >> $GITHUB_OUTPUT + echo "$EOF" >> $GITHUB_OUTPUT + env: + CHANGELOG: ${{ steps.generate-changelog.outputs.changelog }} + REPO_URL: ${{ env.SYNC_TARGET_REPOSITORY }} + shell: bash + + - name: Create PR + id: create-pr + uses: peter-evans/create-pull-request@v6 + with: + token: ${{ steps.generate-token.outputs.token }} + base: ${{ env.BASE_BRANCH }} + branch: sync-tier4-upstream-${{ inputs.sync-target-tag }} + title: "chore: sync upstream up to ${{ inputs.sync-target-tag }}" + body: ${{ steps.replace-pr-number-to-url.outputs.changelog }} + labels: | + bot + sync-tier4-upstream + author: github-actions + signoff: true + delete-branch: true + + - name: Check outputs + run: | + echo "Pull Request Number - ${{ steps.create-pr.outputs.pull-request-number }}" + echo "Pull Request URL - ${{ steps.create-pr.outputs.pull-request-url }}" + + - name: Enable auto-merge + if: ${{ steps.create-pr.outputs.pull-request-operation == 'created' }} + run: gh pr merge --merge --auto "${{ steps.create-pr.outputs.pull-request-number }}" + shell: bash + env: + GITHUB_TOKEN: ${{ steps.generate-token.outputs.token }} From 2a4f27f547ee675a63dae10e77fa283041f26ec4 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 2 Apr 2024 12:09:23 +0900 Subject: [PATCH 846/851] feat: run sync-awf-latest every one hour (#365) Signed-off-by: Takayuki Murooka --- .github/workflows/sync-awf-latest.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/sync-awf-latest.yaml b/.github/workflows/sync-awf-latest.yaml index ba1380ddac..7a5f79acaa 100644 --- a/.github/workflows/sync-awf-latest.yaml +++ b/.github/workflows/sync-awf-latest.yaml @@ -2,7 +2,7 @@ name: sync-awf-latest on: schedule: - - cron: 0 15 * * * + - cron: 50 */1 * * * # every 1 hour (**:50) workflow_dispatch: jobs: From 3f2a5a0bb96d5012afdc21020c591c01d833e5c0 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 4 Apr 2024 20:01:22 +0900 Subject: [PATCH 847/851] fix: cherry-pick necessary changes from tier4/main (#368) Signed-off-by: Takayuki Murooka --- .../components/tier4_autoware_api_component.launch.xml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml b/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml index 1c7b520108..bc582fbb9a 100644 --- a/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml +++ b/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml @@ -1,7 +1,8 @@ - - + + + From 458c439c9e4d6aeb19bf3fcd323f52eb39a53c68 Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Thu, 11 Apr 2024 00:17:46 +0000 Subject: [PATCH 848/851] chore: sync files (#379) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .pre-commit-config-optional.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.pre-commit-config-optional.yaml b/.pre-commit-config-optional.yaml index 3b43f9ae11..b2d8c5e805 100644 --- a/.pre-commit-config-optional.yaml +++ b/.pre-commit-config-optional.yaml @@ -1,6 +1,6 @@ repos: - repo: https://github.com/tcort/markdown-link-check - rev: v3.11.2 + rev: v3.12.1 hooks: - id: markdown-link-check args: [--quiet, --config=.markdown-link-check.json] From 4422decbd2df0a348ff60c0134bd585b6479282c Mon Sep 17 00:00:00 2001 From: tzhong518 Date: Thu, 18 Apr 2024 09:24:31 +0900 Subject: [PATCH 849/851] fix: add has_variance to pointpainting.param.yaml Signed-off-by: tzhong518 --- .../detection/lidar_model/pointpainting.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml index 3abaffb243..53ac6f4caf 100755 --- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml +++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml @@ -16,6 +16,7 @@ downsample_factor: 1 encoder_in_feature_size: 12 yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] + has_variance: false has_twist: false densification_params: world_frame_id: "map" From 6aed22dc617daa20b728e407af596467af4203fb Mon Sep 17 00:00:00 2001 From: "tier4-autoware-public-bot[bot]" <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Date: Thu, 25 Apr 2024 00:18:34 +0000 Subject: [PATCH 850/851] chore: sync files (#391) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/PULL_REQUEST_TEMPLATE/small-change.md | 4 ++++ .github/PULL_REQUEST_TEMPLATE/standard-change.md | 13 +++++++++++++ 2 files changed, 17 insertions(+) diff --git a/.github/PULL_REQUEST_TEMPLATE/small-change.md b/.github/PULL_REQUEST_TEMPLATE/small-change.md index 2ff933c43a..e15fdd992d 100644 --- a/.github/PULL_REQUEST_TEMPLATE/small-change.md +++ b/.github/PULL_REQUEST_TEMPLATE/small-change.md @@ -15,6 +15,10 @@ Not applicable. Not applicable. +## Interface changes + + + ## Pre-review checklist for the PR author The PR author **must** check the checkboxes below when creating the PR. diff --git a/.github/PULL_REQUEST_TEMPLATE/standard-change.md b/.github/PULL_REQUEST_TEMPLATE/standard-change.md index 7aedefd0a7..391af62975 100644 --- a/.github/PULL_REQUEST_TEMPLATE/standard-change.md +++ b/.github/PULL_REQUEST_TEMPLATE/standard-change.md @@ -18,6 +18,19 @@ +### ROS Topic Changes + + + + + + +### ROS Parameter Changes + + + + + ## Effects on system behavior From 499913fbc629f8fc206bf290bb7041d9d4f39c13 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Thu, 2 May 2024 11:05:01 +0900 Subject: [PATCH 851/851] ci: add comment-on-pr.yaml (#400) --- .github/workflows/comment-on-pr.yaml | 25 +++++++++++++++++++++++++ 1 file changed, 25 insertions(+) create mode 100644 .github/workflows/comment-on-pr.yaml diff --git a/.github/workflows/comment-on-pr.yaml b/.github/workflows/comment-on-pr.yaml new file mode 100644 index 0000000000..3cfec4bf14 --- /dev/null +++ b/.github/workflows/comment-on-pr.yaml @@ -0,0 +1,25 @@ +name: comment-on-pr + +on: + pull_request: + types: + - opened + branches: + - beta/v0.[0-9]+.[1-9]+ + +jobs: + comment: + runs-on: ubuntu-latest + steps: + - name: Create comments + run: | + cat << EOF > comments + ### Merging guidelines for the beta branch + Please use `Squash and merge` as the default. + However, when incorporating multiple changes with cherry-pick, use a `Create a merge commit` to preserve the changes in the history. + EOF + - name: Post comments + env: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} + URL: ${{ github.event.pull_request.html_url }} + run: gh pr comment -F ./comments "${URL}"