diff --git a/.github/workflows/comment-on-pr.yaml b/.github/workflows/comment-on-pr.yaml
new file mode 100644
index 0000000000..471f8bf5a5
--- /dev/null
+++ b/.github/workflows/comment-on-pr.yaml
@@ -0,0 +1,30 @@
+name: comment-on-pr
+
+on:
+ pull_request:
+ types:
+ - opened
+ branches:
+ - beta/v[0-9]+.[0-9]+.[0-9]+
+
+jobs:
+ comment:
+ runs-on: ubuntu-latest
+ steps:
+ - name: Create comments
+ run: |
+ cat << 'EOF' > comments
+ ### betaブランチへマージする際のガイドライン
+ 通常は`Squash and merge`を使用してください。
+ ただし、cherry-pickで複数の変更を取り込むときには、変更履歴を残すために`Create a merge commit`を使用してください。
+
+ ### Merging guidelines for the beta branch
+ Please use `Squash and merge` as the default.
+ However, when incorporating multiple changes with cherry-pick, use a `Create a merge commit` to preserve the changes in the history.
+ EOF
+
+ - name: Post comments
+ env:
+ GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }}
+ URL: ${{ github.event.pull_request.html_url }}
+ run: gh pr comment -F ./comments "${URL}"
diff --git a/autoware_launch/config/control/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml b/autoware_launch/config/control/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml
index a4e8ab2c83..8ed57b0a35 100644
--- a/autoware_launch/config/control/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml
+++ b/autoware_launch/config/control/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml
@@ -1,17 +1,17 @@
/**:
ros__parameters:
- transition_timeout: 10.0
+ transition_timeout: 6.0
frequency_hz: 10.0
# set true if you want to engage the autonomous driving mode while the vehicle is driving. If set to false, it will deny Engage in any situation where the vehicle speed is not zero. Note that if you use this feature without adjusting the parameters, it may cause issues like sudden deceleration. Before using, please ensure the engage condition and the vehicle_cmd_gate transition filter are appropriately adjusted.
- enable_engage_on_driving: false
+ enable_engage_on_driving: true
- check_engage_condition: false # set false if you do not want to care about the engage condition.
+ check_engage_condition: true # set false if you do not want to care about the engage condition.
nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index
nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index
engage_acceptable_limits:
allow_autonomous_in_stopped: true # no check if the velocity is zero, always allowed.
- dist_threshold: 1.5
+ dist_threshold: 0.5
yaw_threshold: 0.524
speed_upper_threshold: 10.0
speed_lower_threshold: -10.0
@@ -19,8 +19,8 @@
lateral_acc_threshold: 1.0
lateral_acc_diff_threshold: 0.5
stable_check:
- duration: 0.1
- dist_threshold: 1.5
+ duration: 3.0
+ dist_threshold: 0.5
speed_upper_threshold: 2.0
speed_lower_threshold: -2.0
yaw_threshold: 0.262
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 8e28e37780..7c68630fe9 100644
--- a/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml
+++ b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml
@@ -7,7 +7,7 @@
admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value
# -- path smoothing --
- enable_path_smoothing: false # flag for path smoothing
+ enable_path_smoothing: true # flag for path smoothing
path_filter_moving_ave_num: 25 # param of moving average filter for path smoothing
curvature_smoothing_num_traj: 15 # point-to-point index distance used in curvature calculation (for trajectory): curvature is calculated from three points p(i-num), p(i), p(i+num)
curvature_smoothing_num_ref_steer: 15 # point-to-point index distance used in curvature calculation (for steer command reference): curvature is calculated from three points p(i-num), p(i), p(i+num)
@@ -49,7 +49,7 @@
vehicle_model_steer_tau: 0.15 # steering dynamics time constant (1d approximation) [s]
steer_rate_lim_dps_list_by_curvature: [40.0, 50.0, 60.0] # steering angle rate limit list depending on curvature [deg/s]
curvature_list_for_steer_rate_lim: [0.001, 0.002, 0.01] # curvature list for steering angle rate limit interpolation in ascending order [/m]
- steer_rate_lim_dps_list_by_velocity: [60.0, 50.0, 40.0] # steering angle rate limit list depending on velocity [deg/s]
+ steer_rate_lim_dps_list_by_velocity: [10.0, 10.0, 10.0] # steering angle rate limit list depending on velocity [deg/s]
velocity_list_for_steer_rate_lim: [10.0, 15.0, 20.0] # velocity list for steering angle rate limit interpolation in ascending order [m/s]
acceleration_limit: 2.0 # acceleration limit for trajectory velocity modification [m/ss]
velocity_time_constant: 0.3 # velocity dynamics time constant for trajectory velocity modification [s]
@@ -69,7 +69,7 @@
# steer offset
steering_offset:
- enable_auto_steering_offset_removal: true
+ enable_auto_steering_offset_removal: false
update_vel_threshold: 5.56
update_steer_threshold: 0.035
average_num: 1000
diff --git a/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
index 8d774a3fa0..4970271629 100644
--- a/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
+++ b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
@@ -6,7 +6,7 @@
enable_overshoot_emergency: true
enable_large_tracking_error_emergency: true
enable_slope_compensation: true
- enable_keep_stopped_until_steer_convergence: true
+ enable_keep_stopped_until_steer_convergence: false
# state transition
drive_state_stop_dist: 0.5
@@ -15,7 +15,7 @@
stopped_state_entry_duration_time: 0.1
stopped_state_entry_vel: 0.01
stopped_state_entry_acc: 0.1
- emergency_state_overshoot_stop_dist: 1.5
+ emergency_state_overshoot_stop_dist: 0.8
emergency_state_traj_trans_dev: 3.0
emergency_state_traj_rot_dev: 0.7854
@@ -39,9 +39,9 @@
brake_keeping_acc: -0.2
# smooth stop state
- smooth_stop_max_strong_acc: -0.5
- smooth_stop_min_strong_acc: -0.8
- smooth_stop_weak_acc: -0.3
+ smooth_stop_max_strong_acc: -0.8
+ smooth_stop_min_strong_acc: -1.3
+ smooth_stop_weak_acc: -0.6
smooth_stop_weak_stop_acc: -0.8
smooth_stop_strong_stop_acc: -3.4
smooth_stop_max_fast_vel: 0.5
@@ -67,7 +67,7 @@
# jerk limit
max_jerk: 2.0
- min_jerk: -2.0
+ min_jerk: -5.0
# pitch
use_trajectory_for_pitch_calculation: true
diff --git a/autoware_launch/config/localization/ekf_localizer.param.yaml b/autoware_launch/config/localization/ekf_localizer.param.yaml
index 2a3489ee97..c470003de5 100644
--- a/autoware_launch/config/localization/ekf_localizer.param.yaml
+++ b/autoware_launch/config/localization/ekf_localizer.param.yaml
@@ -24,9 +24,9 @@
# for diagnostics
pose_no_update_count_threshold_warn: 50
- pose_no_update_count_threshold_error: 100
+ pose_no_update_count_threshold_error: 250
twist_no_update_count_threshold_warn: 50
- twist_no_update_count_threshold_error: 100
+ twist_no_update_count_threshold_error: 250
# for velocity measurement limitation (Set 0.0 if you want to ignore)
- threshold_observable_velocity_mps: 0.0 # [m/s]
+ threshold_observable_velocity_mps: 0.5 # [m/s]
diff --git a/autoware_launch/config/perception/object_recognition/detection/detection_by_tracker/detection_by_tracker.param.yaml b/autoware_launch/config/perception/object_recognition/detection/detection_by_tracker/detection_by_tracker.param.yaml
index 6957040506..d78887b29d 100644
--- a/autoware_launch/config/perception/object_recognition/detection/detection_by_tracker/detection_by_tracker.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/detection_by_tracker/detection_by_tracker.param.yaml
@@ -2,7 +2,7 @@
ros__parameters:
tracker_ignore_label:
UNKNOWN : true
- CAR : false
+ CAR : true
TRUCK : false
BUS : false
TRAILER : false
diff --git a/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml b/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml
index 69ff96a263..898391ce5d 100644
--- a/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml
@@ -1,7 +1,7 @@
/**:
ros__parameters:
enable_delay_compensation: true
- prediction_time_horizon: 10.0 #[s]
+ prediction_time_horizon: 18.0 #[s]
lateral_control_time_horizon: 5.0 #[s]
prediction_sampling_delta_time: 0.5 #[s]
min_velocity_for_map_based_prediction: 1.39 #[m/s]
diff --git a/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml
index c0cad93c6a..53c20b5813 100644
--- a/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml
+++ b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml
@@ -1,16 +1,16 @@
/**:
ros__parameters:
- additional_lidars: ["front_upper", "front_lower"]
+ additional_lidars: []
ransac_input_topics: []
use_single_frame_filter: False
use_time_series_filter: True
common_crop_box_filter:
parameters:
- min_x: -100.0
- max_x: 150.0
- min_y: -70.0
- max_y: 70.0
+ min_x: -70.0
+ max_x: 120.0
+ min_y: -75.0
+ max_y: 75.0
max_z: 3.2
min_z: -2.5 # recommended 0.0 for non elevation_grid_mode
negative: False
diff --git a/autoware_launch/config/perception/occupancy_grid_map/binary_bayes_filter_updater.param.yaml b/autoware_launch/config/perception/occupancy_grid_map/binary_bayes_filter_updater.param.yaml
index 4e335e3574..6237b6fed6 100644
--- a/autoware_launch/config/perception/occupancy_grid_map/binary_bayes_filter_updater.param.yaml
+++ b/autoware_launch/config/perception/occupancy_grid_map/binary_bayes_filter_updater.param.yaml
@@ -5,4 +5,4 @@
occupied_to_free: 0.05
free_to_occupied: 0.2
free_to_free: 0.8
- v_ratio: 10.0
+ v_ratio: 4.5
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 03958fda9a..5fd1a533ab 100644
--- a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml
@@ -4,8 +4,8 @@
normal:
min_acc: -1.0 # min deceleration [m/ss]
max_acc: 1.0 # max acceleration [m/ss]
- min_jerk: -1.0 # min jerk [m/sss]
- max_jerk: 1.0 # max jerk [m/sss]
+ min_jerk: -0.3 # min jerk [m/sss]
+ max_jerk: 0.6 # max jerk [m/sss]
slow_down:
min_acc: -1.0 # min deceleration [m/ss]
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 c759ead2c8..96be6b05cb 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
@@ -26,7 +26,7 @@
# engage & replan parameters
replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s]
engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed)
- engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement)
+ engage_acceleration: 0.6 # engage acceleration [m/ss] (use this acceleration when engagement)
engage_exit_ratio: 0.5 # exit engage sequence to normal velocity planning when the velocity exceeds engage_exit_ratio x engage_velocity.
stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [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 41d1bd02a7..74b6a4f6ca 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
@@ -32,20 +32,20 @@
moving_time_threshold: 1.0 # [s]
max_expand_ratio: 0.0 # [-]
envelope_buffer_margin: 0.3 # [m]
- avoid_margin_lateral: 0.0 # [m]
- safety_buffer_lateral: 0.8 # [m]
+ avoid_margin_lateral: 1.0 # [m]
+ safety_buffer_lateral: 0.1 # [m]
safety_buffer_longitudinal: 0.0 # [m]
- use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance.
+ use_conservative_buffer_longitudinal: false # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance.
truck:
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
- avoid_margin_lateral: 0.0
- safety_buffer_lateral: 0.8
+ avoid_margin_lateral: 1.0
+ safety_buffer_lateral: 0.4
safety_buffer_longitudinal: 0.0
- use_conservative_buffer_longitudinal: true
+ use_conservative_buffer_longitudinal: false
bus:
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
@@ -55,7 +55,7 @@
avoid_margin_lateral: 0.0
safety_buffer_lateral: 0.8
safety_buffer_longitudinal: 0.0
- use_conservative_buffer_longitudinal: true
+ use_conservative_buffer_longitudinal: false
trailer:
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
@@ -65,8 +65,9 @@
avoid_margin_lateral: 0.0
safety_buffer_lateral: 0.8
safety_buffer_longitudinal: 0.0
- use_conservative_buffer_longitudinal: true
+ use_conservative_buffer_longitudinal: false
unknown:
+ is_target: false
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
@@ -75,37 +76,37 @@
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
- use_conservative_buffer_longitudinal: true
+ use_conservative_buffer_longitudinal: false
bicycle:
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
- envelope_buffer_margin: 0.8
+ envelope_buffer_margin: 0.3
avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
- use_conservative_buffer_longitudinal: true
+ use_conservative_buffer_longitudinal: false
motorcycle:
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
- envelope_buffer_margin: 0.8
+ envelope_buffer_margin: 0.3
avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
- use_conservative_buffer_longitudinal: true
+ use_conservative_buffer_longitudinal: false
pedestrian:
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
- envelope_buffer_margin: 0.8
+ envelope_buffer_margin: 0.3
avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
- use_conservative_buffer_longitudinal: true
+ use_conservative_buffer_longitudinal: false
lower_distance_for_polygon_expansion: 30.0 # [m]
upper_distance_for_polygon_expansion: 100.0 # [m]
@@ -122,9 +123,9 @@
motorcycle: true # [-]
pedestrian: true # [-]
# detection range
- object_check_goal_distance: 20.0 # [m]
+ object_check_goal_distance: 0.0 # [m]
# filtering parking objects
- threshold_distance_object_is_on_center: 1.0 # [m]
+ threshold_distance_object_is_on_center: 0.5 # [m]
object_check_shiftable_ratio: 0.6 # [-]
object_check_min_road_shoulder_width: 0.5 # [m]
# lost object compensation
@@ -188,7 +189,7 @@
expected_rear_deceleration: -1.0 # [m/ss]
rear_vehicle_reaction_time: 2.0 # [s]
rear_vehicle_safety_time_margin: 1.0 # [s]
- lateral_distance_max_threshold: 0.75 # [m]
+ lateral_distance_max_threshold: 1.25 # [m]
longitudinal_distance_min_threshold: 3.0 # [m]
longitudinal_velocity_delta_time: 0.8 # [s]
@@ -199,8 +200,8 @@
lateral_execution_threshold: 0.09 # [m]
lateral_small_shift_threshold: 0.101 # [m]
lateral_avoid_check_threshold: 0.1 # [m]
- soft_road_shoulder_margin: 0.8 # [m]
- hard_road_shoulder_margin: 0.8 # [m]
+ soft_road_shoulder_margin: 0.3 # [m]
+ hard_road_shoulder_margin: 0.3 # [m]
max_right_shift_length: 5.0
max_left_shift_length: 5.0
max_deviation_from_lane: 0.5 # [m]
@@ -216,7 +217,7 @@
return_dead_line:
goal:
enable: true # [-]
- buffer: 25.0 # [m]
+ buffer: 0.0 # [m]
traffic_light:
enable: true # [-]
buffer: 3.0 # [m]
@@ -255,8 +256,8 @@
lateral:
velocity: [1.0, 1.38, 11.1] # [m/s]
max_accel_values: [0.5, 0.5, 0.5] # [m/ss]
- min_jerk_values: [0.2, 0.2, 0.2] # [m/sss]
- max_jerk_values: [1.0, 1.0, 1.0] # [m/sss]
+ min_jerk_values: [0.1, 0.1, 0.2] # [m/sss]
+ max_jerk_values: [0.2, 0.2, 1.0] # [m/sss]
# longitudinal constraints
longitudinal:
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml
index 0558f6c606..5942477bd3 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml
@@ -26,7 +26,7 @@
left: 0.5 # [m] extra length to add to the left of the dynamic object footprint
right: 0.5 # [m] extra length to add to the rear of the dynamic object footprint
path_preprocessing:
- max_arc_length: 100.0 # [m] maximum arc length along the path where the ego footprint is projected (0.0 means no limit)
+ max_arc_length: 80.0 # [m] maximum arc length along the path where the ego footprint is projected (0.0 means no limit)
resample_interval: 2.0 # [m] fixed interval between resampled path points (0.0 means path points are directly used)
reuse_max_deviation: 0.5 # [m] if the path changes by more than this value, the curvatures are recalculated. Otherwise they are reused.
avoid_linestring:
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 fefbe85607..06fe74e3b7 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
@@ -41,7 +41,7 @@
# pull over
pull_over:
- minimum_request_length: 10.0
+ minimum_request_length: 0.0
pull_over_velocity: 3.0
pull_over_minimum_velocity: 1.38
decide_path_distance: 10.0
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 ce9477b173..3959c78361 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
@@ -4,13 +4,13 @@
backward_lane_length: 200.0 #[m]
prepare_duration: 3.0 # [s]
- backward_length_buffer_for_end_of_lane: 0.5 # [m]
- backward_length_buffer_for_blocking_object: 3.0 # [m]
+ backward_length_buffer_for_end_of_lane: 7.0 # [m]
+ backward_length_buffer_for_blocking_object: 0.5 # [m]
lane_change_finish_judge_buffer: 0.0 # [m]
- lane_changing_lateral_jerk: 0.75 # [m/s3]
+ lane_changing_lateral_jerk: 0.3 # [m/s3]
- minimum_lane_changing_velocity: 1.0 # [m/s]
+ minimum_lane_changing_velocity: 1.5 # [m/s]
prediction_time_resolution: 0.5 # [s]
longitudinal_acceleration_sampling_num: 5
lateral_acceleration_sampling_num: 3
@@ -24,8 +24,8 @@
length_ratio_for_turn_signal_deactivation: 0.8 # ratio (desired end position)
# longitudinal acceleration
- min_longitudinal_acc: -1.0
- max_longitudinal_acc: 1.0
+ min_longitudinal_acc: -0.5
+ max_longitudinal_acc: 0.2
# safety check
safety_check:
@@ -39,6 +39,14 @@
longitudinal_distance_min_threshold: 3.0
longitudinal_velocity_delta_time: 0.8
cancel:
+ expected_front_deceleration: -1.0
+ expected_rear_deceleration: -2.5
+ rear_vehicle_reaction_time: 1.0
+ rear_vehicle_safety_time_margin: 0.5
+ lateral_distance_max_threshold: 0.75
+ longitudinal_distance_min_threshold: 2.0
+ longitudinal_velocity_delta_time: 0.3
+ stuck:
expected_front_deceleration: -1.0
expected_rear_deceleration: -2.0
rear_vehicle_reaction_time: 1.5
@@ -46,25 +54,17 @@
lateral_distance_max_threshold: 1.0
longitudinal_distance_min_threshold: 2.5
longitudinal_velocity_delta_time: 0.6
- stuck:
- 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
# lane expansion for object filtering
lane_expansion:
- left_offset: 0.0 # [m]
- right_offset: 0.0 # [m]
+ left_offset: 1.0 # [m]
+ right_offset: 1.0 # [m]
# lateral acceleration map
lateral_acceleration:
velocity: [0.0, 4.0, 10.0]
min_values: [0.15, 0.15, 0.15]
- max_values: [1.25, 1.25, 1.25]
+ max_values: [0.5, 0.5, 0.5]
# target object
target_object:
@@ -72,17 +72,27 @@
truck: true
bus: true
trailer: true
- unknown: true
+ unknown: false
bicycle: true
motorcycle: true
- pedestrian: true
+ pedestrian: false
# collision check
enable_prepare_segment_collision_check: false
prepare_segment_ignore_object_velocity_thresh: 0.1 # [m/s]
check_objects_on_current_lanes: true
- check_objects_on_other_lanes: true
- use_all_predicted_path: true
+ check_objects_on_other_lanes: false
+ use_all_predicted_path: false
+
+ # lane change regulations
+ regulation:
+ crosswalk: true
+ intersection: false
+
+ # ego vehicle stuck detection
+ stuck_detection:
+ velocity: 0.5 # [m/s]
+ stop_time: 3.0 # [s]
# lane change regulations
regulation:
@@ -98,8 +108,8 @@
# lane change cancel
cancel:
enable_on_prepare_phase: true
- enable_on_lane_changing_phase: true
- delta_time: 1.0 # [s]
+ enable_on_lane_changing_phase: false
+ delta_time: 2.0 # [s]
duration: 5.0 # [s]
max_lateral_jerk: 100.0 # [m/s3]
overhang_tolerance: 0.0 # [m]
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 0090a29926..2c7adeb2f7 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
@@ -6,7 +6,7 @@
external_request_lane_change_left:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
- enable_simultaneous_execution_as_candidate_module: true
+ enable_simultaneous_execution_as_candidate_module: false
keep_last: false
priority: 6
max_module_size: 1
@@ -14,7 +14,7 @@
external_request_lane_change_right:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
- enable_simultaneous_execution_as_candidate_module: true
+ enable_simultaneous_execution_as_candidate_module: false
keep_last: false
priority: 6
max_module_size: 1
@@ -22,17 +22,17 @@
lane_change_left:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
- enable_simultaneous_execution_as_candidate_module: true
+ enable_simultaneous_execution_as_candidate_module: false
keep_last: false
- priority: 5
+ priority: 4
max_module_size: 1
lane_change_right:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
- enable_simultaneous_execution_as_candidate_module: true
+ enable_simultaneous_execution_as_candidate_module: false
keep_last: false
- priority: 5
+ priority: 4
max_module_size: 1
start_planner:
@@ -60,15 +60,17 @@
max_module_size: 1
avoidance:
- enable_rtc: false
- enable_simultaneous_execution_as_approved_module: true
+ enable_module: true
+ enable_rtc: true
+ enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
- priority: 4
+ priority: 5
max_module_size: 1
avoidance_by_lc:
- enable_rtc: false
+ enable_module: false
+ enable_rtc: true
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
@@ -76,7 +78,8 @@
max_module_size: 1
dynamic_avoidance:
- enable_rtc: false
+ enable_module: false
+ enable_rtc: true
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_velocity_planner/crosswalk.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml
index e7bdda45de..35a932565e 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
@@ -53,12 +53,12 @@
stop_object_velocity_threshold: 0.28 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.28 m/s = 1.0 kmph)
min_object_velocity: 1.39 # [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV. 1.39 m/s = 5.0 kmph)
## param for yielding
- disable_stop_for_yield_cancel: false # for the crosswalks with traffic signal
- disable_yield_for_new_stopped_object: false # for the crosswalks with traffic signal
- # If the pedestrian does not move for X seconds after the ego has stopped in front the crosswalk, the module judge that the pedestrian has no intention to walk and allows the ego to proceed.
+ disable_stop_for_yield_cancel: true # for the crosswalk where there is a traffic signal
+ disable_yield_for_new_stopped_object: true # for the crosswalk where there is a traffic signal
+ # 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] If the ego maintains the stop for this amount of time, then the ego proceeds, assuming it has stopped long time enough.
+ 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
object_filtering:
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 3649964bbb..bbdb6de2c4 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
@@ -12,10 +12,12 @@
max_accel: -2.8
max_jerk: -5.0
delay_response_time: 0.5
+ disable_pass_judge_sudden_stop: true
+ enable_peeking_pass_judge: false
stuck_vehicle:
turn_direction:
- left: true
+ left: false
right: true
straight: true
use_stuck_stopline: true
@@ -54,10 +56,10 @@
collision_end_margin_time: 2.0
yield_on_green_traffic_light:
distance_to_assigned_lanelet_start: 10.0
- duration: 3.0
- object_dist_to_stopline: 10.0
+ duration: 8.0
+ object_dist_to_stopline: 10.0 # [m]
ignore_on_amber_traffic_light:
- object_expected_deceleration: 2.0
+ object_expected_deceleration: 2.0 # [m/ss]
ignore_on_red_traffic_light:
object_margin_to_path: 2.0
@@ -90,6 +92,6 @@
intersection_to_occlusion: false
merge_from_private:
- stopline_margin: 0.5
- stop_duration_sec: 1.0
+ stopline_margin: 1.7
+ stop_duration_sec: 1.5
stop_distance_threshold: 1.0
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml
index 5fa183d73a..0d4e806c2f 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/stop_line.param.yaml
@@ -1,7 +1,7 @@
/**:
ros__parameters:
stop_line:
- stop_margin: 0.0
+ stop_margin: 0.5
stop_duration_sec: 1.0
use_initialization_stop_line_state: true
hold_stop_margin_distance: 2.0
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 23746a61b6..6c6d66f5e7 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
@@ -1,9 +1,15 @@
/**:
ros__parameters:
traffic_light:
- stop_margin: 0.0
+ stop_margin: 0.5
tl_state_timeout: 1.0
stop_time_hysteresis: 0.1
yellow_lamp_period: 2.75
enable_pass_judge: true
- 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
+ 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
+
+ v2i:
+ use_rest_time: true
+ last_time_allowed_to_pass: 2.0 # relative time against at the time of turn to red
+ velocity_threshold: 0.5 # change the decision logic whether the current velocity is faster or not
+ required_time_to_departure: 3.0 # prevent low speed pass
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/walkway.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/walkway.param.yaml
index 2bdfacd868..778d685141 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/walkway.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/walkway.param.yaml
@@ -2,4 +2,4 @@
ros__parameters:
walkway:
stop_duration: 0.1 # [s] stop time at stop position
- stop_distance_from_crosswalk: 0.0 # [m] make stop line away from crosswalk when no explicit stop line exists
+ stop_distance_from_crosswalk: 1.5 # [m] make stop line away from crosswalk when no explicit stop line exists
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_replayer/rtc_replayer.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_replayer/rtc_replayer.param.yaml
index c0e3e147dc..8f16690498 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_replayer/rtc_replayer.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_replayer/rtc_replayer.param.yaml
@@ -11,8 +11,8 @@
- "lane_change_right"
- "avoidance_left"
- "avoidance_right"
- - "avoidance_by_lane_change_left"
- - "avoidance_by_lane_change_right"
+ # - "avoidance_by_lane_change_left"
+ # - "avoidance_by_lane_change_right"
- "goal_planner"
- "start_planner"
- "intersection_occlusion"
@@ -28,8 +28,8 @@
- "lane_change_right"
# - "avoidance_left"
# - "avoidance_right"
- - "avoidance_by_lane_change_left"
- - "avoidance_by_lane_change_right"
+ # - "avoidance_by_lane_change_left"
+ # - "avoidance_by_lane_change_right"
- "goal_planner"
- "start_planner"
- "intersection_occlusion"
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml
index 55939fd00b..7164c0c3c6 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml
@@ -3,7 +3,7 @@
option:
enable_skip_optimization: false # skip elastic band and model predictive trajectory
enable_reset_prev_optimization: false # If true, optimization has no fix constraint to the previous result.
- enable_outside_drivable_area_stop: true # stop if the ego's trajectory footprint is outside the drivable area
+ enable_outside_drivable_area_stop: false # stop if the ego's trajectory footprint is outside the drivable area
use_footprint_polygon_for_outside_drivable_area_check: false # If false, only the footprint's corner points are considered.
debug:
@@ -44,14 +44,14 @@
enable_optimization_validation: false
common:
- num_points: 100 # number of points for optimization [-]
- delta_arc_length: 0.5 # delta arc length for optimization [m]
+ num_points: 50 # number of points for optimization [-]
+ delta_arc_length: 1.0 # delta arc length for optimization [m]
kinematics:
# If this parameter is commented out, the parameter is set as below by default.
# The logic could be `optimization_center_offset = vehicle_info.wheelbase * 0.8`
# The 0.8 scale is adopted as it performed the best.
- optimization_center_offset: 2.0 # optimization center offset from base link
+ optimization_center_offset: 0.0 # optimization center offset from base link
clearance: # clearance(distance) between vehicle and roads/objects when generating trajectory
# if collision_free_constraints.option.hard_constraint is true
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 7c2e59e58d..4e70cd2901 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
@@ -19,11 +19,11 @@
nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index
nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index
- min_behavior_stop_margin: 3.0 # [m]
+ min_behavior_stop_margin: 6.0 # [m]
stop_on_curve:
- enable_approaching: false
- additional_safe_distance_margin: 3.0 # [m]
- min_safe_distance_margin: 3.0 # [m]
+ enable_approaching: true
+ additional_safe_distance_margin: 2.0 # [m]
+ min_safe_distance_margin: 3.5 # [m]
suppress_sudden_obstacle_stop: true
stop_obstacle_type:
@@ -178,6 +178,7 @@
# parameters to calculate slow down velocity by linear interpolation
labels:
- "default"
+ - "pedestrian"
default:
moving:
min_lat_margin: 0.2
@@ -189,7 +190,17 @@
max_lat_margin: 0.7
min_ego_velocity: 2.0
max_ego_velocity: 8.0
-
+ pedestrian:
+ moving:
+ min_lat_margin: 0.5
+ max_lat_margin: 1.0
+ min_ego_velocity: 2.0
+ max_ego_velocity: 4.0
+ static:
+ min_lat_margin: 0.5
+ max_lat_margin: 1.0
+ min_ego_velocity: 2.0
+ max_ego_velocity: 4.0
moving_object_speed_threshold: 0.5 # [m/s] how fast the object needs to move to be considered as "moving"
moving_object_hysteresis_range: 0.1 # [m/s] hysteresis range used to prevent chattering when obstacle moves close to moving_object_speed_threshold
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml
index 5ec10572ff..4ef3a456b7 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml
@@ -9,7 +9,7 @@
surround_check_side_distance: 0.5
surround_check_back_distance: 0.5
unknown:
- enable_check: true
+ enable_check: false
surround_check_front_distance: 0.5
surround_check_side_distance: 0.5
surround_check_back_distance: 0.5
@@ -49,9 +49,9 @@
surround_check_side_distance: 0.5
surround_check_back_distance: 0.5
- surround_check_hysteresis_distance: 0.3
+ surround_check_hysteresis_distance: 0.1
- state_clear_time: 2.0
+ state_clear_time: 0.2
# ego stop state
stop_state_ego_speed: 0.1 #[m/s]
diff --git a/autoware_launch/config/system/component_state_monitor/topics.yaml b/autoware_launch/config/system/component_state_monitor/topics.yaml
index f8c6f9685f..5a8958566e 100644
--- a/autoware_launch/config/system/component_state_monitor/topics.yaml
+++ b/autoware_launch/config/system/component_state_monitor/topics.yaml
@@ -72,7 +72,7 @@
topic_type: sensor_msgs/msg/PointCloud2
best_effort: true
transient_local: false
- warn_rate: 5.0
+ warn_rate: 6.5
error_rate: 1.0
timeout: 1.0
diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml
index 990ff17d13..8beba58b20 100644
--- a/autoware_launch/launch/autoware.launch.xml
+++ b/autoware_launch/launch/autoware.launch.xml
@@ -43,7 +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 7fb68a02f5..c398131012 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -29,6 +29,9 @@
+
+
+