diff --git a/.github/labeler.yaml b/.github/labeler.yaml
new file mode 100644
index 0000000000..412523c3a3
--- /dev/null
+++ b/.github/labeler.yaml
@@ -0,0 +1,33 @@
+"type:ci":
+ - .github/**/*
+ - "*.json"
+ - "*.yaml"
+ - "*.cfg"
+ - .clang-format
+ - .gitignore
+ - .prettierignore
+"type:documentation":
+ - "**/*.md"
+ - "**/*.rst"
+ - "**/*.jpg"
+ - "**/*.png"
+ - "**/*.svg"
+"component:control":
+ - "**/*control*"
+"component:localization":
+ - "**/*localization*"
+"component:map":
+ - "**/*map*"
+"component:perception":
+ - "**/*perception*"
+"component:planning":
+ - "**/*planning*"
+"component:sensing":
+ - "**/*sensing*"
+"component:simulation":
+ - "**/*simulator*"
+"component:system":
+ - "**/*system*"
+"component:ui":
+ - "**/*.rviz"
+ - "**/rviz"
diff --git a/.github/workflows/pr-labeler.yaml b/.github/workflows/pr-labeler.yaml
new file mode 100644
index 0000000000..d45067bee5
--- /dev/null
+++ b/.github/workflows/pr-labeler.yaml
@@ -0,0 +1,16 @@
+name: pr-labeler
+on:
+ pull_request_target:
+ types:
+ - opened
+ - edited
+ - synchronize
+
+jobs:
+ label:
+ runs-on: ubuntu-latest
+ steps:
+ - uses: actions/labeler@v4
+ with:
+ repo-token: ${{ secrets.GITHUB_TOKEN }}
+ configuration-path: .github/labeler.yaml
diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml
index 5ad60de003..4197506ed9 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.8.0
+ rev: v0.9.0
hooks:
- id: flake8-ros
- id: prettier-xacro
diff --git a/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml b/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
index c81ce46278..68a42383fe 100644
--- a/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
+++ b/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml
@@ -1,22 +1,38 @@
/**:
ros__parameters:
- publish_debug_pointcloud: false
+ # Ego path calculation
use_predicted_trajectory: true
- use_imu_path: true
+ use_imu_path: false
+ min_generated_path_length: 0.5
+ imu_prediction_time_horizon: 1.5
+ imu_prediction_time_interval: 0.1
+ mpc_prediction_time_horizon: 1.5
+ mpc_prediction_time_interval: 0.1
+
+ # Debug
+ publish_debug_pointcloud: false
+
+ # Point cloud partitioning
detection_range_min_height: 0.0
detection_range_max_height_margin: 0.0
voxel_grid_x: 0.05
voxel_grid_y: 0.05
voxel_grid_z: 100000.0
- min_generated_path_length: 0.5
+
+ # Point cloud cropping
expand_width: 0.1
+ path_footprint_extra_margin: 4.0
+
+ # Point cloud clustering
+ cluster_tolerance: 0.1 #[m]
+ minimum_cluster_size: 10
+ maximum_cluster_size: 10000
+
+ # RSS distance collision check
longitudinal_offset: 2.0
t_response: 1.0
a_ego_min: -3.0
a_obj_min: -1.0
- imu_prediction_time_horizon: 1.5
- imu_prediction_time_interval: 0.1
- mpc_prediction_time_horizon: 1.5
- mpc_prediction_time_interval: 0.1
collision_keeping_sec: 2.0
+ previous_obstacle_keep_time: 1.0
aeb_hz: 10.0
diff --git a/autoware_launch/config/localization/ekf_localizer.param.yaml b/autoware_launch/config/localization/ekf_localizer.param.yaml
index 1ebe5cfd6d..2684fd1604 100644
--- a/autoware_launch/config/localization/ekf_localizer.param.yaml
+++ b/autoware_launch/config/localization/ekf_localizer.param.yaml
@@ -13,13 +13,13 @@
pose_additional_delay: 0.0
pose_measure_uncertainty_time: 0.01
pose_smoothing_steps: 5
- pose_gate_dist: 10000.0
+ pose_gate_dist: 49.5 # corresponds to significance level = 10^-10
twist_measurement:
# for twist measurement
twist_additional_delay: 0.0
twist_smoothing_steps: 2
- twist_gate_dist: 10000.0
+ twist_gate_dist: 46.1 # corresponds to significance level = 10^-10
process_noise:
# for process model
diff --git a/autoware_launch/config/localization/ndt_scan_matcher/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher/ndt_scan_matcher.param.yaml
index 77843e379b..69e0e77bba 100644
--- a/autoware_launch/config/localization/ndt_scan_matcher/ndt_scan_matcher.param.yaml
+++ b/autoware_launch/config/localization/ndt_scan_matcher/ndt_scan_matcher.param.yaml
@@ -47,7 +47,7 @@
# The number of initial random trials in the TPE (Tree-Structured Parzen Estimator).
# This value should be equal to or less than 'initial_estimate_particles_num' and more than 0.
# If it is equal to 'initial_estimate_particles_num', the search will be the same as a full random search.
- n_startup_trials: 20
+ n_startup_trials: 100
validation:
diff --git a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_pointcloud_fusion.param.yaml b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_pointcloud_fusion.param.yaml
index 5b86b8e81d..acf5f75163 100644
--- a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_pointcloud_fusion.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_pointcloud_fusion.param.yaml
@@ -2,4 +2,5 @@
ros__parameters:
fuse_unknown_only: true
min_cluster_size: 2
+ max_cluster_size: 20
cluster_2d_tolerance: 0.5
diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml
index 7d8bff69b4..0777ddb92b 100644
--- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml
@@ -1,28 +1,20 @@
/**:
ros__parameters:
- class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
- rename_car_to_truck_and_bus: true
- point_feature_size: 4
- 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: 9
- # post-process params
- circle_nms_dist_threshold: 0.3
- iou_nms_target_class_names: ["CAR", "TRUCK", "BUS"]
- iou_nms_search_distance_2d: 10.0
- iou_nms_threshold: 0.1
- yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
- score_threshold: 0.35
- has_variance: false
- has_twist: false
- trt_precision: fp16
- densification_num_past_frames: 1
- densification_world_frame_id: map
# weight files
encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
+ trt_precision: fp16
+ post_process_params:
+ # post-process params
+ circle_nms_dist_threshold: 0.5
+ iou_nms_target_class_names: ["CAR"]
+ iou_nms_search_distance_2d: 10.0
+ iou_nms_threshold: 0.1
+ yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
+ score_threshold: 0.35
+ densification_params:
+ world_frame_id: map
+ num_past_frames: 1
diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml
index 35e11e61e9..0777ddb92b 100644
--- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml
@@ -1,27 +1,20 @@
/**:
ros__parameters:
- class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
- point_feature_size: 4
- max_voxel_size: 40000
- point_cloud_range: [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0]
- voxel_size: [0.32, 0.32, 10.0]
- downsample_factor: 2
- encoder_in_feature_size: 9
- # post-process params
- circle_nms_dist_threshold: 0.5
- iou_nms_target_class_names: ["CAR"]
- iou_nms_search_distance_2d: 10.0
- iou_nms_threshold: 0.1
- yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
- score_threshold: 0.35
- has_variance: false
- has_twist: false
- trt_precision: fp16
- densification_num_past_frames: 1
- densification_world_frame_id: map
# weight files
encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
+ trt_precision: fp16
+ post_process_params:
+ # post-process params
+ circle_nms_dist_threshold: 0.5
+ iou_nms_target_class_names: ["CAR"]
+ iou_nms_search_distance_2d: 10.0
+ iou_nms_threshold: 0.1
+ yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
+ score_threshold: 0.35
+ densification_params:
+ world_frame_id: map
+ num_past_frames: 1
diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/detection_class_remapper.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/detection_class_remapper.param.yaml
deleted file mode 100644
index baea087c96..0000000000
--- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/detection_class_remapper.param.yaml
+++ /dev/null
@@ -1,38 +0,0 @@
-/**:
- ros__parameters:
- allow_remapping_by_area_matrix:
- # NOTE(kl): We turn all vehicles into trailers if they go over 3x12 [m^2].
- # NOTE(kl): We turn cars into trucks if they have an area between 2.2 x 5.5 and 3.0 * 12.0 [m^2]
- # row: original class. column: class to remap to
- #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
- [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
- 0, 0, 1, 0, 1, 0, 0, 0, #CAR
- 0, 0, 0, 0, 1, 0, 0, 0, #TRUCK
- 0, 0, 0, 0, 1, 0, 0, 0, #BUS
- 0, 0, 0, 0, 0, 0, 0, 0, #TRAILER
- 0, 0, 0, 0, 0, 0, 0, 0, #MOTORBIKE
- 0, 0, 0, 0, 0, 0, 0, 0, #BICYCLE
- 0, 0, 0, 0, 0, 0, 0, 0] #PEDESTRIAN
-
- min_area_matrix:
- #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
- 0.000, 0.000, 12.100, 0.000, 36.000, 0.000, 0.000, 0.000, #CAR
- 0.000, 0.000, 0.000, 0.000, 36.000, 0.000, 0.000, 0.000, #TRUCK
- 0.000, 0.000, 0.000, 0.000, 36.000, 0.000, 0.000, 0.000, #BUS
- 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER
- 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE
- 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE
- 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #PEDESTRIAN
-
-
- max_area_matrix:
- #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
- 0.000, 0.000, 36.000, 0.000, 999.999, 0.000, 0.000, 0.000, #CAR
- 0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #TRUCK
- 0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #BUS
- 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER
- 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE
- 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE
- 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #PEDESTRIAN
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
old mode 100755
new mode 100644
index 53ac6f4caf..de46b6dd74
--- 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,33 +1,21 @@
/**:
ros__parameters:
- trt_precision: fp16
encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
-
- 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_variance: false
- has_twist: false
- densification_params:
- world_frame_id: "map"
- num_past_frames: 0
+ trt_precision: fp16
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.35
+ score_threshold: 0.45
+ yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
+ densification_params:
+ world_frame_id: "map"
+ num_past_frames: 1
omp_params:
# omp params
num_threads: 1
diff --git a/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml b/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml
index 7ea6217b1f..83778f14ab 100644
--- a/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml
@@ -27,6 +27,9 @@
timeout_set_for_no_intention_to_walk: [1.0, 0.0] # [s] values of map
# parameter for shoulder lane prediction
prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8
+ use_crosswalk_user_history:
+ match_lost_and_appeared_users: false
+ remember_lost_users: false
# parameters for lc prediction
lane_change_detection:
diff --git a/autoware_launch/config/perception/occupancy_grid_map/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml b/autoware_launch/config/perception/occupancy_grid_map/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml
index f9a1c4f930..878bea4cd8 100644
--- a/autoware_launch/config/perception/occupancy_grid_map/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml
+++ b/autoware_launch/config/perception/occupancy_grid_map/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml
@@ -12,6 +12,10 @@
map_length_x: 150.0 # [m]
map_length_y: 150.0 # [m]
+ # downsample input pointcloud
+ downsample_input_pointcloud: true
+ downsample_voxel_size: 0.25 # [m]
+
# each grid map parameters
ogm_creation_config:
height_filter:
@@ -20,7 +24,7 @@
max_height: 2.0
enable_single_frame_mode: true
# use sensor pointcloud to filter obstacle pointcloud
- filter_obstacle_pointcloud_by_raw_pointcloud: true
+ filter_obstacle_pointcloud_by_raw_pointcloud: false
grid_map_type: "OccupancyGridMapFixedBlindSpot"
OccupancyGridMapFixedBlindSpot:
diff --git a/autoware_launch/config/perception/occupancy_grid_map/pointcloud_based_occupancy_grid_map.param.yaml b/autoware_launch/config/perception/occupancy_grid_map/pointcloud_based_occupancy_grid_map.param.yaml
index e8344bee3a..f418b2aef4 100644
--- a/autoware_launch/config/perception/occupancy_grid_map/pointcloud_based_occupancy_grid_map.param.yaml
+++ b/autoware_launch/config/perception/occupancy_grid_map/pointcloud_based_occupancy_grid_map.param.yaml
@@ -8,6 +8,10 @@
min_height: -1.0
max_height: 2.0
+ # downsample input pointcloud
+ downsample_input_pointcloud: true
+ downsample_voxel_size: 0.125 # [m]
+
enable_single_frame_mode: false
# use sensor pointcloud to filter obstacle pointcloud
filter_obstacle_pointcloud_by_raw_pointcloud: false
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 f2289d0776..e8d8be5335 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
@@ -132,6 +132,10 @@
th_shiftable_ratio: 0.8 # [-]
min_road_shoulder_width: 0.5 # [m] FOR DEVELOPER
+ # for merging/deviating vehicle
+ merging_vehicle:
+ th_overhang_distance: 0.0 # [m]
+
# params for avoidance of vehicle type objects that are ambiguous as to whether they are parked.
avoidance_for_ambiguous_vehicle:
enable: true # [-]
@@ -290,4 +294,3 @@
# for debug
debug:
marker: false
- console: false
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 6dee628c59..b43179c844 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
@@ -1,6 +1,5 @@
/**:
ros__parameters:
- verbose: false
max_iteration_num: 100
traffic_light_signal_timeout: 1.0
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml
index 0a563498be..c1f4646ef7 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml
@@ -12,9 +12,9 @@
bus: true
trailer: true
unknown: false
- bicycle: false
+ bicycle: true
motorcycle: true
- pedestrian: false
+ pedestrian: true
max_obstacle_vel: 100.0 # [m/s]
min_obstacle_vel: 0.0 # [m/s]
@@ -40,6 +40,7 @@
max_overtaking_object_angle: 1.05
min_oncoming_object_vel: 1.0
max_oncoming_object_angle: 0.523
+ max_pedestrian_crossing_vel: 0.8
front_object:
max_object_angle: 0.785
@@ -55,6 +56,10 @@
min_longitudinal_polygon_margin: 3.0 # [m]
lat_offset_from_obstacle: 1.0 # [m]
+ margin_distance_around_pedestrian: 2.0 # [m]
+ predicted_path:
+ end_time_to_consider: 3.0 # [s]
+ threshold_confidence: 0.0 # [] not probability
max_lat_offset_to_avoid: 0.5 # [m]
max_time_for_object_lat_shift: 0.0 # [s]
lpf_gain_for_lat_avoid_to_offset: 0.9 # [-]
diff --git a/autoware_launch/config/planning/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
index 82a586d7b7..7cada2de35 100644
--- a/autoware_launch/config/planning/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
@@ -43,6 +43,7 @@
ego_pass_later_margin_x: [0.0] # [[s]] time to vehicle margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition)
ego_pass_later_margin_y: [13.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition)
ego_pass_later_additional_margin: 0.5 # [s] additional time margin for object pass first situation to suppress chattering
+ ego_min_assumed_speed: 2.0 # [m/s] assumed speed to calculate the time to collision point
no_stop_decision: # parameters to determine if it is safe to attempt stopping before the crosswalk
max_offset_to_crosswalk_for_yield: 0.0 # [m] maximum offset from ego's front to crosswalk for yield. Positive value means in front of the crosswalk.
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 c918aa3772..f550636892 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
@@ -101,7 +101,7 @@
creep_velocity: 0.8333
peeking_offset: -0.5
occlusion_required_clearance_distance: 55.0
- possible_object_bbox: [1.75, 2.5]
+ possible_object_bbox: [1.9, 2.5]
ignore_parked_vehicle_speed_threshold: 0.8333
occlusion_detection_hold_time: 1.5
temporal_stop_time_before_peeking: 0.1
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml
index 689775ab91..b13df72409 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml
@@ -3,6 +3,7 @@
out_of_lane: # module to stop or slowdown before overlapping another lane with other objects
mode: ttc # mode used to consider a conflict with an object. "threshold", "intervals", or "ttc"
skip_if_already_overlapping: false # do not run this module when ego already overlaps another lane
+ ignore_overlaps_over_lane_changeable_lanelets: true # if true, overlaps on lane changeable lanelets are ignored
threshold:
time_threshold: 5.0 # [s] consider objects that will reach an overlap within this time
diff --git a/autoware_launch/config/planning/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
index 9c2bc5106f..b7dbf48d0f 100644
--- a/autoware_launch/config/planning/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
@@ -87,7 +87,7 @@
obstacle_traj_angle_threshold : 1.22 # [rad] = 70 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop
stop:
- max_lat_margin: 0.2 # lateral margin between obstacle and trajectory band with ego's width
+ max_lat_margin: 0.3 # lateral margin between obstacle and trajectory band with ego's width
crossing_obstacle:
collision_time_margin : 4.0 # time threshold of collision between obstacle adn ego for cruise or stop [s]
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_sampler/path_sampler.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_sampler/path_sampler.param.yaml
index d22ce0e6b4..0471ee13aa 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_sampler/path_sampler.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_sampler/path_sampler.param.yaml
@@ -8,25 +8,30 @@
id: 0 # id of the candidate paths for which to print/show details (e.g., footprint in rviz)
preprocessing:
- force_zero_initial_deviation: True # if true, initial planning starts from the reference path
- force_zero_initial_heading: True # if true, initial planning starts with a heading aligned with the reference path
+ force_zero_initial_deviation: False # if true, initial planning starts from the reference path
+ force_zero_initial_heading: False # if true, initial planning starts with a heading aligned with the reference path
smooth_reference_trajectory: False # if true, the reference trajectory is smoothed before being used for planning
constraints:
hard:
max_curvature: 0.1 # [m⁻¹] maximum curvature of a sampled path
min_curvature: -0.1 # [m⁻¹] minimum curvature of a sampled path
+ min_distance_from_obstacles: 0.5 # [m] min allowed distance from obstacles
+ limit_footprint_inside_drivable_area: false # if true, paths where the ego footprint exits the drivable area are rejected
soft:
lateral_deviation_weight: 1.0 # cost weight for lateral deviation between the end of a sampled path and the reference path
length_weight: 1.0 # cost weight for the length of a sampled path
curvature_weight: 1.0 # cost weight for the curvature of a sampled path
+ path_reuse:
+ maximum_lateral_deviation: 1.0 # [m] reset the previous path if ego deviates from it by more than this value
+ direct_reuse_distance: 2.0 # [m] a new path is generated only after ego travels this distance along the previously calculated path, or if it has become invalid
sampling:
enable_frenet: True
enable_bezier: True
resolution: 0.5 # [m] target distance between sampled path points
previous_path_reuse_points_nb: 2 # number of points reused from the previously generated path (0:no reuse, 1:replan from end of prev path, 2: end and mid of prev path, etc)
target_lengths: [10.0, 20.0] # [m] target lengths of the sampled paths
- nb_target_lateral_positions: 2 # number of lateral positions to use for sampling (in addition to 0.0 and the current lateral deviation)
- target_lateral_positions: [-0.5, 0.0, 0.5] # manual values that are only used if nb_target_lateral_positions = 0
+ nb_target_lateral_positions: 0 # number of lateral positions to use for sampling (in addition to 0.0 and the current lateral deviation)
+ target_lateral_positions: [-2.0, -1.5, -1.0, -0.5, 0.0, 0.5, 1.0, 1.5, 2.0] # manual values that are only used if nb_target_lateral_positions = 0
frenet: # target values for the sampled "lateral deviation over longitudinal position" polynomial
target_lateral_velocities: [-0.1, 0.0, 0.1]
target_lateral_accelerations: [0.0]
diff --git a/autoware_launch/config/simulator/fault_injection.param.yaml b/autoware_launch/config/simulator/fault_injection.param.yaml
index ac02442d70..d608a7ab11 100644
--- a/autoware_launch/config/simulator/fault_injection.param.yaml
+++ b/autoware_launch/config/simulator/fault_injection.param.yaml
@@ -3,7 +3,7 @@
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_matching_score_is_low: "scan_matching_status"
localization_accuracy_is_low: "localization_error_ellipse"
map_version_is_different: "map_version"
trajectory_is_invalid: "trajectory_point_validation"
diff --git a/autoware_launch/config/system/component_state_monitor/topics.yaml b/autoware_launch/config/system/component_state_monitor/topics.yaml
index 83aa09f615..f4463dc71f 100644
--- a/autoware_launch/config/system/component_state_monitor/topics.yaml
+++ b/autoware_launch/config/system/component_state_monitor/topics.yaml
@@ -154,19 +154,6 @@
error_rate: 1.0
timeout: 1.0
-- module: localization
- mode: [online, logging_simulation]
- type: autonomous
- args:
- node_name_suffix: pose_estimator_pose
- topic: /localization/pose_estimator/pose_with_covariance
- topic_type: geometry_msgs/msg/PoseWithCovarianceStamped
- best_effort: false
- transient_local: false
- warn_rate: 2.0
- error_rate: 1.0
- timeout: 1.0
-
- module: perception
mode: [online, logging_simulation, planning_simulation]
type: launch
diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml
index 3a571d323a..9ff7c1b5fa 100644
--- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml
+++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml
@@ -26,7 +26,7 @@
# /autoware/control/external_control/local_external_control/device_connection: 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/scan_matching_status: { sf_at: "warn", lf_at: "none", spf_at: "none" }
/autoware/localization/performance_monitoring/localization_error_ellipse: { sf_at: "warn", lf_at: "none", spf_at: "none" }
/autoware/localization/performance_monitoring/localization_stability: { sf_at: "warn", lf_at: "none", spf_at: "none" }
/autoware/localization/performance_monitoring/sensor_fusion_status: { sf_at: "warn", lf_at: "none", spf_at: "none" }
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 85fa57bf4f..a7b174bafa 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
@@ -26,7 +26,7 @@
/autoware/control/external_control/local_external_control/device_connection: 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/scan_matching_status: { sf_at: "warn", lf_at: "none", spf_at: "none" }
/autoware/localization/performance_monitoring/localization_error_ellipse: default
/autoware/localization/performance_monitoring/localization_stability: default
/autoware/localization/performance_monitoring/sensor_fusion_status: { sf_at: "error", lf_at: "none", spf_at: "none" }
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 43ddd792b8..afdc066659 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
@@ -25,7 +25,7 @@
/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/scan_matching_status: { sf_at: "warn", lf_at: "none", spf_at: "none" }
# /autoware/localization/performance_monitoring/localization_error_ellipse: default
/autoware/map/node_alive_monitoring: default
diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml
index fe2183434f..77cd324c51 100644
--- a/autoware_launch/launch/autoware.launch.xml
+++ b/autoware_launch/launch/autoware.launch.xml
@@ -21,6 +21,7 @@
+
@@ -136,7 +137,7 @@
-
+
diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz
index e13201aaa5..0a40f390d4 100644
--- a/autoware_launch/rviz/autoware.rviz
+++ b/autoware_launch/rviz/autoware.rviz
@@ -250,18 +250,18 @@ Visualization Manager:
Enabled: true
Gear Topic Test: /vehicle/status/gear_status
Hazard Lights Topic: /vehicle/status/hazard_lights_status
- Height: 175
- Left: 10
+ Height: 100
+ Left: 0
Name: SignalDisplay
Signal Color: 0; 230; 120
Speed Limit Topic: /planning/scenario_planning/current_max_velocity
Speed Topic: /vehicle/status/velocity_status
Steering Topic: /vehicle/status/steering_status
Top: 10
- Traffic Topic: /perception/traffic_light_recognition/traffic_signals
+ Traffic Topic: /planning/scenario_planning/lane_driving/behavior_planning/debug/traffic_signal
Turn Signals Topic: /vehicle/status/turn_indicators_status
Value: true
- Width: 517
+ Width: 550
Enabled: true
Name: Vehicle
- Class: rviz_plugins/MrmSummaryOverlayDisplay
@@ -930,6 +930,14 @@ Visualization Manager:
Reliability Policy: Reliable
Value: /planning/mission_planning/echo_back_goal_pose
Value: true
+ - Class: autoware_mission_details_overlay_rviz_plugin/MissionDetailsDisplay
+ Name: MissionDetailsDisplay
+ Width: 170
+ Height: 100
+ Right: 10
+ Top: 10
+ Remaining Distance and Time Topic: /planning/mission_remaining_distance_time
+ Enabled: true
Enabled: true
Name: MissionPlanning
- Class: rviz_common/Group