From b4b75db11b50c84b0325ac84413c1a0fd9b364a4 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi Date: Tue, 16 Jul 2024 09:45:10 +0900 Subject: [PATCH 1/4] chore: 60kmph params Signed-off-by: Shumpei Wakabayashi --- .../vehicle_cmd_gate/vehicle_cmd_gate.param.yaml | 2 +- .../scenario_planning/common/common.param.yaml | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml b/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml index 8b11cdb85a..fcddd4a1bf 100644 --- a/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml +++ b/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml @@ -23,7 +23,7 @@ lat_jerk_lim: [7.0, 7.0, 7.0, 6.0] actual_steer_diff_lim: [1.0, 1.0, 1.0, 0.8] on_transition: - vel_lim: 50.0 + vel_lim: 60.0 reference_speed_points: [20.0, 30.0] steer_lim: [1.0, 0.8] steer_rate_lim: [1.0, 0.8] 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 5680a99713..afd28238f3 100644 --- a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml @@ -1,17 +1,17 @@ /**: ros__parameters: - max_vel: 11.1 # max velocity limit [m/s] + max_vel: 16.8 # max velocity limit [m/s] # constraints param for normal driving normal: min_acc: -1.0 # min deceleration [m/ss] - max_acc: 1.0 # max acceleration [m/ss] + max_acc: 1.5 # max acceleration [m/ss] min_jerk: -1.0 # min jerk [m/sss] - max_jerk: 1.0 # max jerk [m/sss] + max_jerk: 1.5 # max jerk [m/sss] # constraints to be observed limit: min_acc: -2.5 # min deceleration limit [m/ss] - max_acc: 1.0 # max acceleration limit [m/ss] + max_acc: 2.0 # max acceleration limit [m/ss] min_jerk: -1.5 # min jerk limit [m/sss] - max_jerk: 1.5 # max jerk limit [m/sss] + max_jerk: 2.5 # max jerk limit [m/sss] From e52b37513729e54ad74aca9c472d44ad9fc8573a Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi Date: Mon, 29 Jul 2024 11:56:16 +0900 Subject: [PATCH 2/4] tmp 60kmph Signed-off-by: Shumpei Wakabayashi --- .../velocity_smoother.param.yaml | 2 +- .../scenario_planning/common/common.param.yaml | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/velocity_smoother.param.yaml b/autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/velocity_smoother.param.yaml index ff97ae8dfb..b7e666763c 100644 --- a/autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/velocity_smoother.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/velocity_smoother.param.yaml @@ -42,7 +42,7 @@ max_trajectory_length: 200.0 # max 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_resample_dt: 0.05 # 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/autoware_launch/config/planning/scenario_planning/common/common.param.yaml b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml index afd28238f3..831169a10b 100644 --- a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml @@ -4,14 +4,14 @@ # constraints param for normal driving normal: - min_acc: -1.0 # min deceleration [m/ss] + min_acc: -2.0 # min deceleration [m/ss] max_acc: 1.5 # max acceleration [m/ss] - min_jerk: -1.0 # min jerk [m/sss] - max_jerk: 1.5 # max jerk [m/sss] + min_jerk: -2.0 # min jerk [m/sss] + max_jerk: 2.5 # max jerk [m/sss] # constraints to be observed limit: min_acc: -2.5 # min deceleration limit [m/ss] max_acc: 2.0 # max acceleration limit [m/ss] - min_jerk: -1.5 # min jerk limit [m/sss] - max_jerk: 2.5 # max jerk limit [m/sss] + min_jerk: -2.5 # min jerk limit [m/sss] + max_jerk: 3.5 # max jerk limit [m/sss] From e0b239730fc06131913d6cfcfdce296f16ad8aa2 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Wed, 2 Oct 2024 23:31:14 +0900 Subject: [PATCH 3/4] Update autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml --- .../config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml b/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml index fcddd4a1bf..8b11cdb85a 100644 --- a/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml +++ b/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml @@ -23,7 +23,7 @@ lat_jerk_lim: [7.0, 7.0, 7.0, 6.0] actual_steer_diff_lim: [1.0, 1.0, 1.0, 0.8] on_transition: - vel_lim: 60.0 + vel_lim: 50.0 reference_speed_points: [20.0, 30.0] steer_lim: [1.0, 0.8] steer_rate_lim: [1.0, 0.8] From b507c1abfb527f38b82a676e96f05974dd1e7264 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Wed, 2 Oct 2024 23:32:40 +0900 Subject: [PATCH 4/4] Update autoware_launch/config/planning/scenario_planning/common/common.param.yaml --- .../config/planning/scenario_planning/common/common.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 831169a10b..9cc8c6adfa 100644 --- a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml @@ -1,6 +1,6 @@ /**: ros__parameters: - max_vel: 16.8 # max velocity limit [m/s] + max_vel: 13.9 # max velocity limit [m/s] # constraints param for normal driving normal: