From ad51559b1d9b9251630dbd0bba7c3756e9062bf5 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 16 May 2023 12:25:10 +0900 Subject: [PATCH 1/2] feat(path_sampler): add parameter file for the `path_sampler` node (#322) Signed-off-by: Maxime CLEMENT --- .../path_sampler/path_sampler.param.yaml | 39 +++++++++++++++++++ .../tier4_planning_component.launch.xml | 1 + 2 files changed, 40 insertions(+) create mode 100644 autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_sampler/path_sampler.param.yaml 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 new file mode 100644 index 0000000000..b50602b8e6 --- /dev/null +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_sampler/path_sampler.param.yaml @@ -0,0 +1,39 @@ +/**: + ros__parameters: + common: + output_delta_arc_length: 0.5 # [m] delta arc length for output trajectory + + debug: + enable_calculation_time_info: false # flag to print calculation times + 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 + 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 + soft: + lateral_deviation_weight: 0.1 # 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 + 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 + 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] + bezier: + nb_k: 3 # number of sampled curvature values + mk_min: 0.0 # minimum curvature value + mk_max: 10.0 # maximum curvature value + nb_t: 5 # number of sampled acceleration values + mt_min: 0.3 # minimum acceleration value + mt_max: 1.7 # maximum acceleration value diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml index 24237d0dfd..6db13f5259 100644 --- a/autoware_launch/launch/components/tier4_planning_component.launch.xml +++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml @@ -106,6 +106,7 @@ name="obstacle_avoidance_planner_param_path" value="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml" /> + Date: Tue, 16 May 2023 14:29:06 +0900 Subject: [PATCH 2/2] feat(autoware_launch): add lane change abort param (#351) * feat(autoware_launch): add lane change abort param Signed-off-by: Fumiya Watanabe * fix(autoware_launch): restore some parameters Signed-off-by: Fumiya Watanabe --------- Signed-off-by: Fumiya Watanabe --- .../behavior_path_planner/lane_change/lane_change.param.yaml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) 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 c0d895f89f..84a6a36740 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 @@ -37,8 +37,9 @@ enable_cancel_lane_change: true enable_abort_lane_change: false - abort_delta_time: 3.0 # [s] - abort_max_lateral_jerk: 1000.0 # [m/s3] + abort_delta_time: 1.0 # [s] + aborting_time: 5.0 # [s] + abort_max_lateral_jerk: 100.0 # [m/s3] # debug publish_debug_marker: false