diff --git a/autoware_launch/config/control/predicted_path_checker/predicted_path_checker.param.yaml b/autoware_launch/config/control/predicted_path_checker/predicted_path_checker.param.yaml
new file mode 100644
index 0000000000..780d86b5e9
--- /dev/null
+++ b/autoware_launch/config/control/predicted_path_checker/predicted_path_checker.param.yaml
@@ -0,0 +1,22 @@
+/**:
+ ros__parameters:
+ # Node
+ update_rate: 10.0
+ delay_time: 0.17
+ max_deceleration: 1.5
+ resample_interval: 0.5
+ stop_margin: 0.5 # [m]
+ ego_nearest_dist_threshold: 3.0 # [m]
+ ego_nearest_yaw_threshold: 1.046 # [rad] = 60 [deg]
+ min_trajectory_check_length: 1.5 # [m]
+ trajectory_check_time: 3.0
+ distinct_point_distance_threshold: 0.3
+ distinct_point_yaw_threshold: 5.0 # [deg]
+ filtering_distance_threshold: 1.5 # [m]
+ use_object_prediction: true
+
+ collision_checker_params:
+ width_margin: 0.2
+ chattering_threshold: 0.2
+ z_axis_filtering_buffer: 0.3
+ enable_z_axis_obstacle_filtering: false
diff --git a/autoware_launch/config/localization/localization_error_monitor.param.yaml b/autoware_launch/config/localization/localization_error_monitor.param.yaml
index 2aa28014ea..def5c80164 100644
--- a/autoware_launch/config/localization/localization_error_monitor.param.yaml
+++ b/autoware_launch/config/localization/localization_error_monitor.param.yaml
@@ -1,7 +1,7 @@
/**:
ros__parameters:
scale: 3.0
- error_ellipse_size: 1.0
- warn_ellipse_size: 0.8
+ error_ellipse_size: 1.5
+ warn_ellipse_size: 1.2
error_ellipse_size_lateral_direction: 0.3
warn_ellipse_size_lateral_direction: 0.25
diff --git a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml
index 4a22059bda..cf41a4cf55 100644
--- a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml
+++ b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml
@@ -9,6 +9,9 @@
# NDT reference frame
ndt_base_frame: "ndt_base_link"
+ # map frame
+ map_frame: "map"
+
# Subscriber queue size
input_sensor_points_queue_size: 1
@@ -38,7 +41,7 @@
converged_param_nearest_voxel_transformation_likelihood: 2.3
# The number of particles to estimate initial pose
- initial_estimate_particles_num: 100
+ initial_estimate_particles_num: 200
# Tolerance of timestamp difference between current time and sensor pointcloud. [sec]
lidar_topic_timeout_sec: 1.0
@@ -53,7 +56,7 @@
num_threads: 4
# The covariance of output pose
- # Do note that this covariance matrix is empirically derived
+ # Note that this covariance matrix is empirically derived
output_pose_covariance:
[
0.0225, 0.0, 0.0, 0.0, 0.0, 0.0,
@@ -86,5 +89,5 @@
# If lidar_point.z - base_link.z <= this threshold , the point will be removed
z_margin_for_ground_removal: 0.8
- # The execution time which means probably NDT cannot matches scans properly
- critical_upper_bound_exe_time_ms: 100 # [ms]
+ # The execution time which means probably NDT cannot matches scans properly. [ms]
+ critical_upper_bound_exe_time_ms: 100
diff --git a/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml
new file mode 100644
index 0000000000..22999b411f
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml
@@ -0,0 +1,13 @@
+/**:
+ ros__parameters:
+ min_points_num:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [10, 10, 10, 10, 10,10, 10, 10]
+
+ max_points_num:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [10, 10, 10, 10, 10,10, 10, 10]
+
+ min_points_and_distance_ratio:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [800.0, 880.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0]
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 c91ec0e88b..5f80c76111 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
@@ -139,12 +139,16 @@
check_other_object: true # [-]
# collision check parameters
check_all_predicted_path: false # [-]
- time_resolution: 0.5 # [s]
- time_horizon_for_front_object: 3.0 # [s]
- time_horizon_for_rear_object: 10.0 # [s]
safety_check_backward_distance: 100.0 # [m]
hysteresis_factor_expand_rate: 1.5 # [-]
hysteresis_factor_safe_count: 10 # [-]
+ # predicted path parameters
+ min_velocity: 1.38 # [m/s]
+ max_velocity: 50.0 # [m/s]
+ time_resolution: 0.5 # [s]
+ time_horizon_for_front_object: 3.0 # [s]
+ time_horizon_for_rear_object: 10.0 # [s]
+ delay_until_departure: 0.0 # [s]
# rss parameters
expected_front_deceleration: -1.0 # [m/ss]
expected_rear_deceleration: -1.0 # [m/ss]
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 a05bdda099..bf9c815405 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
@@ -16,6 +16,7 @@
motorcycle: true
pedestrian: false
+ max_obstacle_vel: 100.0 # [m/s]
min_obstacle_vel: 0.0 # [m/s]
successive_num_to_entry_dynamic_avoidance_condition: 5
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml
index e1108d56c9..0f1b441bed 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml
@@ -12,14 +12,14 @@
goal_priority: "minimum_weighted_distance" # "minimum_weighted_distance" or "minimum_longitudinal_distance"
minimum_weighted_distance:
lateral_weight: 40.0
- path_priority: "efficient_path" # "efficient_path" or "close_goal"
+ prioritize_goals_before_objects: true
parking_policy: "left_side" # "left_side" or "right_side"
- forward_goal_search_length: 20.0
+ forward_goal_search_length: 40.0
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
+ max_lateral_offset: 1.0
+ lateral_offset_interval: 0.5
ignore_distance_from_lane_start: 0.0
margin_from_boundary: 0.75
@@ -41,12 +41,14 @@
# pull over
pull_over:
- minimum_request_length: 100.0
+ minimum_request_length: 0.0
pull_over_velocity: 3.0
pull_over_minimum_velocity: 1.38
decide_path_distance: 10.0
maximum_deceleration: 1.0
maximum_jerk: 1.0
+ path_priority: "efficient_path" # "efficient_path" or "close_goal"
+ efficient_path_order: ["SHIFT", "ARC_FORWARD", "ARC_BACKWARD"] # only lane based pull over(exculde freespace parking)
# shift parking
shift_parking:
@@ -116,7 +118,7 @@
path_safety_check:
# EgoPredictedPath
ego_predicted_path:
- min_velocity: 0.0
+ min_velocity: 1.0
acceleration: 1.0
max_velocity: 1.0
time_horizon_for_front_object: 10.0
@@ -162,11 +164,11 @@
check_all_predicted_path: true
publish_debug_marker: false
rss_params:
- rear_vehicle_reaction_time: 1.0
+ rear_vehicle_reaction_time: 2.0
rear_vehicle_safety_time_margin: 1.0
- lateral_distance_max_threshold: 1.0
- longitudinal_distance_min_threshold: 1.0
- longitudinal_velocity_delta_time: 1.0
+ lateral_distance_max_threshold: 2.0
+ longitudinal_distance_min_threshold: 3.0
+ longitudinal_velocity_delta_time: 0.8
# hysteresis factor to expand/shrink polygon with the value
hysteresis_factor_expand_rate: 1.0
# temporary
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 1accb1f709..a090a6d3a8 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
@@ -28,15 +28,28 @@
# safety check
safety_check:
- expected_front_deceleration: -1.0
- expected_rear_deceleration: -1.0
- 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
- lateral_distance_max_threshold: 2.0
- longitudinal_distance_min_threshold: 3.0
- longitudinal_velocity_delta_time: 0.8
+ allow_loose_check_for_cancel: true
+ execution:
+ expected_front_deceleration: -1.0
+ expected_rear_deceleration: -1.0
+ rear_vehicle_reaction_time: 2.0
+ rear_vehicle_safety_time_margin: 1.0
+ lateral_distance_max_threshold: 2.0
+ longitudinal_distance_min_threshold: 3.0
+ longitudinal_velocity_delta_time: 0.8
+ cancel:
+ expected_front_deceleration: -1.0
+ expected_rear_deceleration: -2.0
+ rear_vehicle_reaction_time: 1.5
+ rear_vehicle_safety_time_margin: 0.8
+ lateral_distance_max_threshold: 1.0
+ longitudinal_distance_min_threshold: 2.5
+ longitudinal_velocity_delta_time: 0.6
+
+ # lane expansion for object filtering
+ lane_expansion:
+ left_offset: 0.0 # [m]
+ right_offset: 0.0 # [m]
# lateral acceleration map
lateral_acceleration:
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 ff4b486ef9..1fc83edd08 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
@@ -5,7 +5,7 @@
ros__parameters:
external_request_lane_change_left:
enable_module: false
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: true
keep_last: false
@@ -14,7 +14,7 @@
external_request_lane_change_right:
enable_module: false
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: true
keep_last: false
@@ -23,7 +23,7 @@
lane_change_left:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
keep_last: false
@@ -32,7 +32,7 @@
lane_change_right:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
keep_last: false
@@ -41,7 +41,7 @@
start_planner:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
@@ -50,7 +50,7 @@
side_shift:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
@@ -59,7 +59,7 @@
goal_planner:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
keep_last: true
@@ -68,7 +68,7 @@
avoidance:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
@@ -77,7 +77,7 @@
avoidance_by_lc:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
@@ -86,7 +86,7 @@
dynamic_avoidance:
enable_module: false
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
keep_last: true
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 352a0bf350..1424b58d22 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,7 +7,7 @@
collision_check_margin: 1.0
collision_check_distance_from_end: 1.0
th_moving_object_velocity: 1.0
- th_distance_to_middle_of_the_road: 0.1
+ th_distance_to_middle_of_the_road: 0.5
center_line_path_interval: 1.0
# shift pull out
enable_shift_pull_out: true
@@ -21,7 +21,7 @@
maximum_curvature: 0.07
# geometric pull out
enable_geometric_pull_out: true
- divide_pull_out_path: false
+ divide_pull_out_path: true
geometric_pull_out_velocity: 1.0
arc_path_interval: 1.0
lane_departure_margin: 0.2
@@ -127,11 +127,11 @@
check_all_predicted_path: true
publish_debug_marker: false
rss_params:
- rear_vehicle_reaction_time: 1.0
+ rear_vehicle_reaction_time: 2.0
rear_vehicle_safety_time_margin: 1.0
- lateral_distance_max_threshold: 1.0
- longitudinal_distance_min_threshold: 1.0
- longitudinal_velocity_delta_time: 1.0
+ lateral_distance_max_threshold: 2.0
+ longitudinal_distance_min_threshold: 3.0
+ longitudinal_velocity_delta_time: 0.8
# hysteresis factor to expand/shrink polygon
hysteresis_factor_expand_rate: 1.0
# temporary
diff --git a/autoware_launch/config/planning/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
index 8a57bfeabd..0950ece4ae 100644
--- a/autoware_launch/config/planning/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
@@ -8,4 +8,4 @@
max_future_movement_time: 10.0 # [second]
threshold_yaw_diff: 0.523 # [rad]
adjacent_extend_width: 1.5 # [m]
- enable_rtc: true # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
+ enable_rtc: false # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
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 0c12624f3b..d99c70c5f6 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
@@ -5,7 +5,7 @@
show_processing_time: false # [-] whether to show processing time
# param for input data
traffic_light_state_timeout: 3.0 # [s] timeout threshold for traffic light signal
- enable_rtc: true # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
+ enable_rtc: false # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
# param for stop position
stop_position:
@@ -54,7 +54,9 @@
## param for yielding
disable_stop_for_yield_cancel: false # for the crosswalk where there is a traffic signal
disable_yield_for_new_stopped_object: false # for the crosswalk where there is a traffic signal
- timeout_no_intention_to_walk: 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.
+ # if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first.
+ distance_map_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order
+ timeout_map_for_no_intention_to_walk: [3.0, 0.0] # [s]
timeout_ego_stop_for_yield: 3.0 # [s] the amount of time which ego should be stopping to query whether it yields or not
# param for target object filtering
diff --git a/autoware_launch/config/planning/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
index 55b627cce7..ddd8b934d2 100644
--- a/autoware_launch/config/planning/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
@@ -8,4 +8,4 @@
state_clear_time: 2.0
hold_stop_margin_distance: 0.0
distance_to_judge_over_stop_line: 0.5
- enable_rtc: true # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
+ enable_rtc: false # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
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 a932254140..4b8f15ab27 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
@@ -19,6 +19,7 @@
# enable_front_car_decel_prediction: false # By default this feature is disabled
# assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of front car when front car as well as ego are turning
timeout_private_area: 3.0 # [s] cancel stuck vehicle stop in private area
+ enable_private_area_stuck_disregard: false #In the intersections which labeled as "private area", the obstacle vehicles judged as "stuck" are neglected if this param is set as true.
collision_detection:
state_transit_margin_time: 1.0
@@ -34,6 +35,12 @@
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
keep_detection_vel_thr: 0.833 # == 3.0km/h. keep detection if ego is ego.vel < keep_detection_vel_thr
+ use_upstream_velocity: true # flag to use the planned velocity profile from the upstream module
+ minimum_upstream_velocity: 0.01 # [m/s] minimum velocity to avoid null division for the stop line from the upstream velocity
+ yield_on_green_traffic_light:
+ distance_to_assigned_lanelet_start: 10.0
+ duration: 3.0
+ range: 50.0 # [m]
occlusion:
enable: false
@@ -52,10 +59,15 @@
ignore_parked_vehicle_speed_threshold: 0.8333 # == 3.0km/h
stop_release_margin_time: 1.5 # [s]
temporal_stop_before_attention_area: false
+ absence_traffic_light:
+ creep_velocity: 1.388 # [m/s]
+ maximum_peeking_distance: 6.0 # [m]
+ attention_lane_crop_curvature_threshold: 0.25
+ attention_lane_curvature_calculation_ds: 0.5
enable_rtc:
- intersection: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval
- intersection_to_occlusion: true
+ intersection: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval
+ intersection_to_occlusion: false
merge_from_private:
stop_line_margin: 3.0
diff --git a/autoware_launch/config/planning/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
index f550188d4f..c84848f8cc 100644
--- a/autoware_launch/config/planning/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
@@ -8,4 +8,4 @@
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)
- enable_rtc: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval
+ enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval
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 510dc86ef6..c74c5b3d87 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
@@ -24,8 +24,7 @@
action: # action to insert in the path if an object causes a conflict at an overlap
skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed
- strict: true # if true, when a decision is taken to avoid entering a lane, the stop point will make sure no lane at all is entered by ego
- # if false, ego stops just before entering a lane but may then be overlapping another lane.
+ precision: 0.1 # [m] precision when inserting a stop pose in the path
distance_buffer: 1.5 # [m] buffer distance to try to keep between the ego footprint and lane
slowdown:
distance_threshold: 30.0 # [m] insert a slowdown when closer than this distance from an overlap
diff --git a/autoware_launch/config/planning/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
index e8e0357daa..a837ae1b46 100644
--- a/autoware_launch/config/planning/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
@@ -5,4 +5,4 @@
tl_state_timeout: 1.0
yellow_lamp_period: 2.75
enable_pass_judge: true
- enable_rtc: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval
+ enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval
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_replayer/rtc_replayer.param.yaml
similarity index 100%
rename from autoware_launch/config/planning/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_replayer/rtc_replayer.param.yaml
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 cb4d6a68c5..ddea1a9b56 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
@@ -179,10 +179,13 @@
slow_down:
# parameters to calculate slow down velocity by linear interpolation
- min_lat_margin: 0.2
- max_lat_margin: 1.0
- min_ego_velocity: 2.0
- max_ego_velocity: 8.0
+ labels:
+ - "default"
+ default:
+ min_lat_margin: 0.2
+ max_lat_margin: 1.0
+ min_ego_velocity: 2.0
+ max_ego_velocity: 8.0
time_margin_on_target_velocity: 1.5 # [s]
diff --git a/autoware_launch/launch/components/tier4_control_component.launch.xml b/autoware_launch/launch/components/tier4_control_component.launch.xml
index 8b29135048..d15e050d7a 100644
--- a/autoware_launch/launch/components/tier4_control_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_control_component.launch.xml
@@ -5,6 +5,7 @@
+
@@ -42,5 +43,7 @@
+
+
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index 342396934c..1ec8f2c22f 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -48,6 +48,10 @@
name="object_recognition_detection_fusion_sync_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml"
/>
+
-
-
-