diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml
index 7fd1cc90fe..bda722c87e 100644
--- a/.github/workflows/pre-commit.yaml
+++ b/.github/workflows/pre-commit.yaml
@@ -5,7 +5,7 @@ on:
jobs:
pre-commit:
- if: ${{ github.event.repository.private }}
+ if: ${{ github.event.repository.private }} # Use pre-commit.ci for public repositories
runs-on: ubuntu-latest
steps:
- name: Generate token
diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml
index d04c26073e..4b9105a923 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.12.0
+ rev: 23.1.0
hooks:
- id: black
args: [--line-length=100]
diff --git a/autoware_launch/config/map/lanelet2_map_loader.param.yaml b/autoware_launch/config/map/lanelet2_map_loader.param.yaml
new file mode 100755
index 0000000000..e3a4fdf81c
--- /dev/null
+++ b/autoware_launch/config/map/lanelet2_map_loader.param.yaml
@@ -0,0 +1,7 @@
+/**:
+ ros__parameters:
+ lanelet2_map_projector_type: MGRS # Options: MGRS, UTM
+ latitude: 40.81187906 # Latitude of map_origin, using in UTM
+ longitude: 29.35810110 # Longitude of map_origin, using in UTM
+
+ center_line_resolution: 5.0 # [m]
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 93f9d522fb..d707a73bce 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
@@ -7,6 +7,8 @@
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]
+ use_predicted_objects: False # whether to use predicted objects [-]
+ publish_obstacle_polygon: False # whether to publish obstacle polygon [-]
stop_planner:
# params for stop position
@@ -17,7 +19,10 @@
# params for detection area
detection_area:
- lateral_margin: 0.0 # margin of vehicle footprint [m]
+ lateral_margin: 0.0 # margin [m]
+ vehicle_lateral_margin: 0.0 # margin of vehicle footprint [m]
+ pedestrian_lateral_margin: 0.0 # margin of pedestrian footprint [m]
+ unknown_lateral_margin: 0.0 # margin of unknown 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]
@@ -33,6 +38,9 @@
# 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]
+ vehicle_lateral_margin: 1.0 # offset from vehicle side edge for expanding the search area of the surrounding point cloud [m]
+ pedestrian_lateral_margin: 1.0 # offset from pedestrian side edge for expanding the search area of the surrounding point cloud [m]
+ unknown_lateral_margin: 1.0 # offset from unknown side edge for expanding the search area of the surrounding point cloud [m]
# params for velocity
target_velocity:
diff --git a/autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml b/autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml
new file mode 100644
index 0000000000..29d577a7ad
--- /dev/null
+++ b/autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml
@@ -0,0 +1,26 @@
+/**:
+ ros__parameters:
+ 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]
diff --git a/autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml b/autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml
new file mode 100644
index 0000000000..0e3391e69e
--- /dev/null
+++ b/autoware_launch/config/tier4_planning_launch/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml
@@ -0,0 +1,31 @@
+/**:
+ ros__parameters:
+ module_list:
+ - "blind_spot"
+ - "crosswalk"
+ - "detection_area"
+ - "intersection"
+ - "no_stopping_area"
+ - "traffic_light"
+ - "ext_request_lane_change_left"
+ - "ext_request_lane_change_right"
+ - "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/autoware_launch/launch/components/tier4_map_component.launch.xml b/autoware_launch/launch/components/tier4_map_component.launch.xml
index cba9c3c0a2..cc015ebbed 100644
--- a/autoware_launch/launch/components/tier4_map_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_map_component.launch.xml
@@ -8,5 +8,6 @@
+