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
diff --git a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml
index e38f75a3f8..365b42c47a 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,18 @@
# Regularization scale factor
regularization_scale_factor: 0.01
+
+ # Dynamic map loading distance
+ dynamic_map_loading_update_distance: 20.0
+
+ # Dynamic map loading loading radius
+ dynamic_map_loading_map_radius: 150.0
+
+ # 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]
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
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]
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
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
+
+
+
+
+
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
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
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
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
diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml
index 45155cfe86..6e814f3158 100644
--- a/autoware_launch/launch/autoware.launch.xml
+++ b/autoware_launch/launch/autoware.launch.xml
@@ -26,7 +26,6 @@
-
@@ -109,31 +108,12 @@
-
-
-
-
-
-
-
-
-
-
+
-
-
-
-
-
-
-
-
+
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..1c7b520108 100644
--- a/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml
@@ -1,9 +1,7 @@
+
-
-
-
-
-
-
-
+
+
+
+
diff --git a/autoware_launch/launch/components/tier4_control_component.launch.xml b/autoware_launch/launch/components/tier4_control_component.launch.xml
index 264deb0ffc..bae5865104 100644
--- a/autoware_launch/launch/components/tier4_control_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_control_component.launch.xml
@@ -1,22 +1,18 @@
-
-
-
-
-
-
+
+
+
+
-
-
-
+
-
+
-
-
-
+
-
+
-
-
-
-
+
+
+
-
+
@@ -47,7 +44,10 @@
name="drivable_area_expansion_param_path"
value="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml"
/>
-
+
-
@@ -49,8 +48,6 @@
-
-
diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml
index 50d7425bf0..870b0578a8 100644
--- a/autoware_launch/launch/logging_simulator.launch.xml
+++ b/autoware_launch/launch/logging_simulator.launch.xml
@@ -24,6 +24,8 @@
+
+
diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml
index 62fc034a6e..770dfb537d 100644
--- a/autoware_launch/launch/planning_simulator.launch.xml
+++ b/autoware_launch/launch/planning_simulator.launch.xml
@@ -9,6 +9,8 @@
+
+