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 @@ + 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 4a47cc89e2..e43553879c 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] 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 @@ + 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 @@ - +