diff --git a/autoware_launch/config/control/external_cmd_selector/external_cmd_selector.param.yaml b/autoware_launch/config/control/external_cmd_selector/external_cmd_selector.param.yaml
index 6556656cc8..3de702aa00 100644
--- a/autoware_launch/config/control/external_cmd_selector/external_cmd_selector.param.yaml
+++ b/autoware_launch/config/control/external_cmd_selector/external_cmd_selector.param.yaml
@@ -1,4 +1,4 @@
/**:
ros__parameters:
update_rate: 10.0
- initial_selector_mode: "local" # ["local", "remote"]
+ initial_selector_mode: "remote" # ["local", "remote"]
diff --git a/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml
index 253737609b..08993907f0 100644
--- a/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml
+++ b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml
@@ -8,10 +8,10 @@
# Node
update_rate: 10.0
visualize_lanelet: false
- include_right_lanes: false
- include_left_lanes: false
- include_opposite_lanes: false
- include_conflicting_lanes: false
+ include_right_lanes: true
+ include_left_lanes: true
+ include_opposite_lanes: true
+ include_conflicting_lanes: true
boundary_types_to_detect: [curbstone]
# Core
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 4222082d40..8e28e37780 100644
--- a/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml
+++ b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml
@@ -45,8 +45,8 @@
# -- vehicle model --
vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics
- input_delay: 0.24 # steering input delay time for delay compensation
- vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approximation) [s]
+ input_delay: 0.17 # steering input delay time for delay compensation
+ 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]
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 c39088753f..8d774a3fa0 100644
--- a/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
+++ b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
@@ -1,6 +1,6 @@
/**:
ros__parameters:
- delay_compensation_time: 0.17
+ delay_compensation_time: 0.15
enable_smooth_stop: true
enable_overshoot_emergency: true
@@ -58,19 +58,19 @@
# emergency state
emergency_vel: 0.0
- emergency_acc: -5.0
- emergency_jerk: -3.0
+ emergency_acc: -2.5
+ emergency_jerk: -1.5
# acceleration limit
- max_acc: 3.0
- min_acc: -5.0
+ max_acc: 1.86
+ min_acc: -3.36
# jerk limit
max_jerk: 2.0
- min_jerk: -5.0
+ min_jerk: -2.0
# pitch
- use_trajectory_for_pitch_calculation: false
+ use_trajectory_for_pitch_calculation: true
lpf_pitch_gain: 0.95
max_pitch_rad: 0.1
min_pitch_rad: -0.1
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 7ad685217f..03ae9a3e99 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
@@ -2,9 +2,9 @@
ros__parameters:
update_rate: 10.0
system_emergency_heartbeat_timeout: 0.5
- use_emergency_handling: false
+ use_emergency_handling: true
check_external_emergency_heartbeat: false
- use_start_request: false
+ use_start_request: true
enable_cmd_limit_filter: true
filter_activated_count_threshold: 5
filter_activated_velocity_threshold: 1.0
diff --git a/autoware_launch/config/localization/crop_box_filter_measurement_range.param.yaml b/autoware_launch/config/localization/crop_box_filter_measurement_range.param.yaml
index ad55423154..be5a50ef0f 100644
--- a/autoware_launch/config/localization/crop_box_filter_measurement_range.param.yaml
+++ b/autoware_launch/config/localization/crop_box_filter_measurement_range.param.yaml
@@ -2,10 +2,10 @@
ros__parameters:
input_frame: "base_link"
output_frame: "base_link"
- min_x: -60.0
- max_x: 60.0
- min_y: -60.0
- max_y: 60.0
+ min_x: -100.0
+ max_x: 100.0
+ min_y: -100.0
+ max_y: 100.0
min_z: -30.0
max_z: 50.0
negative: False
diff --git a/autoware_launch/config/localization/ekf_localizer.param.yaml b/autoware_launch/config/localization/ekf_localizer.param.yaml
index 1c16624605..2a3489ee97 100644
--- a/autoware_launch/config/localization/ekf_localizer.param.yaml
+++ b/autoware_launch/config/localization/ekf_localizer.param.yaml
@@ -1,7 +1,7 @@
/**:
ros__parameters:
show_debug_info: false
- enable_yaw_bias_estimation: true
+ enable_yaw_bias_estimation: false
predict_frequency: 50.0
tf_rate: 50.0
extend_state_step: 50
diff --git a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml
index 0e4c52ba92..6b3ccc14a6 100644
--- a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml
@@ -1,6 +1,6 @@
/**:
ros__parameters:
- input_offset_ms: [61.67, 111.67, 45.0, 28.33, 78.33, 95.0]
+ input_offset_ms: [50.0, 66.67, 83.33, 0.0, 16.67, 33.33]
timeout_ms: 70.0
match_threshold_ms: 50.0
filter_scope_min_x: -100.0
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 b367fef386..c0cad93c6a 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,6 +1,6 @@
/**:
ros__parameters:
- additional_lidars: []
+ additional_lidars: ["front_upper", "front_lower"]
ransac_input_topics: []
use_single_frame_filter: False
use_time_series_filter: True
@@ -11,7 +11,7 @@
max_x: 150.0
min_y: -70.0
max_y: 70.0
- max_z: 2.5
+ max_z: 3.2
min_z: -2.5 # recommended 0.0 for non elevation_grid_mode
negative: False
@@ -19,14 +19,74 @@
plugin: "ground_segmentation::ScanGroundFilterComponent"
parameters:
global_slope_max_angle_deg: 10.0
- local_slope_max_angle_deg: 13.0 # recommended 30.0 for non elevation_grid_mode
+ local_slope_max_angle_deg: 25.0 # recommended 30.0 for non elevation_grid_mode
split_points_distance_tolerance: 0.2
use_virtual_ground_point: True
split_height_distance: 0.2
non_ground_height_threshold: 0.20
+ grid_size_m: 0.2
+ grid_mode_switch_radius: 20.0
+ gnd_grid_buffer_size: 5
+ detection_range_z_max: 3.2
+ elevation_grid_mode: true
+ center_pcl_shift: 0.0
+
+ # common_ground_filter:
+ # plugin: "ground_segmentation::RayGroundFilterComponent"
+ # parameters:
+ # general_max_slope: 10.0
+ # local_max_slope: 10.0
+ # min_height_threshold: 0.2
+
+ front_upper_crop_box_filter:
+ parameters:
+ min_x: -50.0
+ max_x: 100.0
+ min_y: -50.0
+ max_y: 50.0
+ max_z: 3.2 # recommended 2.5 for non elevation_grid_mode
+ min_z: -2.5 # recommended 0.0 for non elevation_grid_mode
+ negative: False
+
+ front_upper_ground_filter:
+ plugin: "ground_segmentation::ScanGroundFilterComponent"
+ parameters:
+ global_slope_max_angle_deg: 10.0
+ local_slope_max_angle_deg: 18.0 # recommended 30.0 for non elevation_grid_mode
+ split_points_distance_tolerance: 0.20 # recommended 0.045 for non elevation_grid_mode
+ split_height_distance: 0.2 # recommended 0.15 for non elevation_grid_mode
+ use_virtual_ground_point: False
+ non_ground_height_threshold: 0.1
+ grid_size_m: 0.1
+ grid_mode_switch_radius: 20.0
+ gnd_grid_buffer_size: 4
+ detection_range_z_max: 3.2
+ center_pcl_shift: 0.0
+ elevation_grid_mode: true
+
+ front_lower_crop_box_filter:
+ parameters:
+ min_x: -50.0
+ max_x: 100.0
+ min_y: -50.0
+ max_y: 50.0
+ max_z: 3.2 # recommended 2.5 for non elevation_grid_mode
+ min_z: -2.5 # recommended 0.0 for non elevation_grid_mode
+ negative: False
+
+ front_lower_ground_filter:
+ plugin: "ground_segmentation::ScanGroundFilterComponent"
+ parameters:
+ global_slope_max_angle_deg: 10.0
+ local_slope_max_angle_deg: 18.0 # recommended 30.0 for non elevation_grid_mode
+ split_points_distance_tolerance: 0.20 # recommended 0.1 for non elevation_grid_mode
+ split_height_distance: 0.2 # recommended 0.05 for non elevation_grid_mode
+ use_virtual_ground_point: False
+ non_ground_height_threshold: 0.1
grid_size_m: 0.1
grid_mode_switch_radius: 20.0
gnd_grid_buffer_size: 4
- detection_range_z_max: 2.5
+ detection_range_z_max: 3.2
+ center_pcl_shift: 0.0
elevation_grid_mode: true
- use_recheck_ground_cluster: true
+ use_recheck_ground_cluster: false
diff --git a/autoware_launch/config/perception/traffic_light_arbiter/traffic_light_arbiter.param.yaml b/autoware_launch/config/perception/traffic_light_arbiter/traffic_light_arbiter.param.yaml
index 5dc2b62eaa..f6263c621a 100644
--- a/autoware_launch/config/perception/traffic_light_arbiter/traffic_light_arbiter.param.yaml
+++ b/autoware_launch/config/perception/traffic_light_arbiter/traffic_light_arbiter.param.yaml
@@ -2,4 +2,4 @@
ros__parameters:
external_time_tolerance: 5.0
perception_time_tolerance: 1.0
- external_priority: false
+ external_priority: true
diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml
index 329714e3d3..232610713f 100644
--- a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml
@@ -17,8 +17,8 @@
kp: 0.3
backward:
- start_jerk: -0.1
- min_jerk_mild_stop: -0.3
+ start_jerk: -0.3
+ min_jerk_mild_stop: -0.5
min_jerk: -1.5
min_acc_mild_stop: -1.0
min_acc: -2.5
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 235c76a5c1..c759ead2c8 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
@@ -1,7 +1,7 @@
/**:
ros__parameters:
# motion state constraints
- max_velocity: 20.0 # max velocity limit [m/s]
+ max_velocity: 9.72 # max velocity limit [m/s]
stop_decel: 0.0 # deceleration at a stop point[m/ss]
# external velocity limit parameter
@@ -12,7 +12,7 @@
curvature_calculation_distance: 5.0 # distance of points while curvature is calculating for the steer rate and lateral acceleration limit [m]
# lateral acceleration limit parameters
enable_lateral_acc_limit: true # To toggle the lateral acc filter on and off. You can switch it dynamically at runtime.
- max_lateral_accel: 1.0 # max lateral acceleration limit [m/ss]
+ max_lateral_accel: 0.6 # max lateral acceleration limit [m/ss]
min_curve_velocity: 2.74 # min velocity at lateral acceleration limit and steering angle rate limit [m/s]
decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit
decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit
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 d50b1ad42c..41d1bd02a7 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,8 +32,8 @@
moving_time_threshold: 1.0 # [s]
max_expand_ratio: 0.0 # [-]
envelope_buffer_margin: 0.3 # [m]
- avoid_margin_lateral: 1.0 # [m]
- safety_buffer_lateral: 0.7 # [m]
+ avoid_margin_lateral: 0.0 # [m]
+ safety_buffer_lateral: 0.8 # [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.
truck:
@@ -42,8 +42,8 @@
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
- avoid_margin_lateral: 1.0
- safety_buffer_lateral: 0.7
+ avoid_margin_lateral: 0.0
+ safety_buffer_lateral: 0.8
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: true
bus:
@@ -52,8 +52,8 @@
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
- avoid_margin_lateral: 1.0
- safety_buffer_lateral: 0.7
+ avoid_margin_lateral: 0.0
+ safety_buffer_lateral: 0.8
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: true
trailer:
@@ -62,8 +62,8 @@
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
- avoid_margin_lateral: 1.0
- safety_buffer_lateral: 0.7
+ avoid_margin_lateral: 0.0
+ safety_buffer_lateral: 0.8
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: true
unknown:
@@ -82,7 +82,7 @@
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.8
- avoid_margin_lateral: 1.0
+ avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
use_conservative_buffer_longitudinal: true
@@ -92,7 +92,7 @@
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.8
- avoid_margin_lateral: 1.0
+ avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
use_conservative_buffer_longitudinal: true
@@ -102,7 +102,7 @@
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.8
- avoid_margin_lateral: 1.0
+ avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
use_conservative_buffer_longitudinal: true
@@ -199,8 +199,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.3 # [m]
- hard_road_shoulder_margin: 0.3 # [m]
+ soft_road_shoulder_margin: 0.8 # [m]
+ hard_road_shoulder_margin: 0.8 # [m]
max_right_shift_length: 5.0
max_left_shift_length: 5.0
max_deviation_from_lane: 0.5 # [m]
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 06fe74e3b7..fefbe85607 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: 0.0
+ minimum_request_length: 10.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 366c093901..ce9477b173 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
@@ -2,15 +2,15 @@
ros__parameters:
lane_change:
backward_lane_length: 200.0 #[m]
- prepare_duration: 4.0 # [s]
+ prepare_duration: 3.0 # [s]
- backward_length_buffer_for_end_of_lane: 3.0 # [m]
+ backward_length_buffer_for_end_of_lane: 0.5 # [m]
backward_length_buffer_for_blocking_object: 3.0 # [m]
- lane_change_finish_judge_buffer: 2.0 # [m]
+ lane_change_finish_judge_buffer: 0.0 # [m]
- lane_changing_lateral_jerk: 0.5 # [m/s3]
+ lane_changing_lateral_jerk: 0.75 # [m/s3]
- minimum_lane_changing_velocity: 2.78 # [m/s]
+ minimum_lane_changing_velocity: 1.0 # [m/s]
prediction_time_resolution: 0.5 # [s]
longitudinal_acceleration_sampling_num: 5
lateral_acceleration_sampling_num: 3
@@ -64,7 +64,7 @@
lateral_acceleration:
velocity: [0.0, 4.0, 10.0]
min_values: [0.15, 0.15, 0.15]
- max_values: [0.5, 0.5, 0.5]
+ max_values: [1.25, 1.25, 1.25]
# target object
target_object:
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 514d61e225..9190f55f6b 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
@@ -29,7 +29,7 @@
backward_velocity: -1.0
pull_out_max_steer_angle: 0.26 # 15deg
# search start pose backward
- enable_back: true
+ enable_back: false
search_priority: "efficient_path" # "efficient_path" or "short_back_distance"
max_back_distance: 30.0
backward_search_resolution: 2.0
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 997addd48d..1e00d2f4a4 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
@@ -90,6 +90,6 @@
intersection_to_occlusion: false
merge_from_private:
- stopline_margin: 3.0
+ stop_line_margin: 0.5
stop_duration_sec: 1.0
stop_distance_threshold: 1.0
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 f21e3d12db..2bdfacd868 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
@@ -1,5 +1,5 @@
/**:
ros__parameters:
walkway:
- stop_duration: 1.0 # [s] stop time at stop position
- stop_distance_from_crosswalk: 3.5 # [m] make stop line away from crosswalk when no explicit stop line exists
+ 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
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 9d761b15ee..c0e3e147dc 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
@@ -26,8 +26,8 @@
- "traffic_light"
- "lane_change_left"
- "lane_change_right"
- - "avoidance_left"
- - "avoidance_right"
+ # - "avoidance_left"
+ # - "avoidance_right"
- "avoidance_by_lane_change_left"
- "avoidance_by_lane_change_right"
- "goal_planner"
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 9ab8f42bcf..55939fd00b 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
@@ -45,13 +45,13 @@
common:
num_points: 100 # number of points for optimization [-]
- delta_arc_length: 1.0 # delta arc length for optimization [m]
+ delta_arc_length: 0.5 # delta arc length for optimization [m]
- # kinematics:
+ 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.3 # optimization center offset from base link
+ optimization_center_offset: 2.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 90e897fda3..7c2e59e58d 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
@@ -13,7 +13,7 @@
min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss]
min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss]
safe_distance_margin : 6.0 # This is also used as a stop margin [m]
- terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m]
+ terminal_safe_distance_margin : 6.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m]
hold_stop_velocity_threshold: 0.01 # The maximum ego velocity to hold stopping [m/s]
hold_stop_distance_threshold: 0.3 # The ego keeps stopping if the distance to stop changes within the threshold [m]
@@ -97,7 +97,7 @@
max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego
slow_down:
- max_lat_margin: 1.1 # lateral margin between obstacle and trajectory band with ego's width
+ max_lat_margin: 0.8 # lateral margin between obstacle and trajectory band with ego's width
lat_hysteresis_margin: 0.2
successive_num_to_entry_slow_down_condition: 5
@@ -181,12 +181,12 @@
default:
moving:
min_lat_margin: 0.2
- max_lat_margin: 1.0
+ max_lat_margin: 0.7
min_ego_velocity: 2.0
max_ego_velocity: 8.0
static:
min_lat_margin: 0.2
- max_lat_margin: 1.0
+ max_lat_margin: 0.7
min_ego_velocity: 2.0
max_ego_velocity: 8.0
diff --git a/autoware_launch/config/simulator/fault_injection.param.yaml b/autoware_launch/config/simulator/fault_injection.param.yaml
index 1a57b852f7..a7d9663acc 100644
--- a/autoware_launch/config/simulator/fault_injection.param.yaml
+++ b/autoware_launch/config/simulator/fault_injection.param.yaml
@@ -35,3 +35,29 @@
/sensing/gnss/node_alive_monitoring: "gnss_connection"
/system/node_alive_monitoring: "system_topic_status"
/vehicle/node_alive_monitoring: "vehicle_topic_status"
+ cpu_frequency: "CPU Frequency"
+ cpu_load_average: "CPU Load Average"
+ gpu_frequency: "GPU Frequency"
+ lidar_blockage_validation: "blockage_validation"
+ lidar_visibility: "left_upper: visibility_validation"
+ memory_usage: "Memory Usage"
+ network_crc_error: "Network CRC Error"
+ network_ip_packet_reassembles_failed: "IP Packet Reassembles Failed"
+ network_traffic: "Network Traffic"
+ perception_topic_status: "perception_topic_status"
+ process_high_load: "High-load"
+ process_high_mem: "High-mem"
+ process_tasks_summary: "Tasks Summary"
+ remote_control_topic_status: "remote_control_topic_status"
+ sensing_topic_status: "sensing_topic_status"
+ storage_connection: "HDD Connection"
+ storage_power_on_hours: "HDD PowerOnHours"
+ storage_read_data_rate: "HDD ReadDataRate"
+ storage_read_iops: "HDD ReadIOPS"
+ storage_recovered_error: "HDD RecoveredError"
+ storage_total_data_written: "HDD TotalDataWritten"
+ storage_write_data_rate: "HDD WriteDataRate"
+ storage_write_iops: "HDD WriteIOPS"
+ trajectory_curvature_validation: "trajectory_curvature_validation"
+ trajectory_interval_validation : "trajectory_interval_validation"
+ trajectory_relative_angle_validation: "trajectory_relative_angle_validation"
diff --git a/autoware_launch/config/system/emergency_handler/emergency_handler.param.yaml b/autoware_launch/config/system/emergency_handler/emergency_handler.param.yaml
index 652a984ce5..d064f2a2dd 100644
--- a/autoware_launch/config/system/emergency_handler/emergency_handler.param.yaml
+++ b/autoware_launch/config/system/emergency_handler/emergency_handler.param.yaml
@@ -7,7 +7,7 @@
timeout_takeover_request: 10.0
use_takeover_request: false
use_parking_after_stopped: false
- use_comfortable_stop: false
+ use_comfortable_stop: true
# setting whether to turn hazard lamp on for each situation
turning_hazard_on:
diff --git a/autoware_launch/config/system/system_error_monitor/diagnostic_aggregator/system.param.yaml b/autoware_launch/config/system/system_error_monitor/diagnostic_aggregator/system.param.yaml
index 27cbe3fed2..5d559b56cb 100644
--- a/autoware_launch/config/system/system_error_monitor/diagnostic_aggregator/system.param.yaml
+++ b/autoware_launch/config/system/system_error_monitor/diagnostic_aggregator/system.param.yaml
@@ -13,3 +13,12 @@
path: storage_error
contains: ["bagpacker"]
timeout: 3.0
+ fms_connection:
+ type: diagnostic_aggregator/AnalyzerGroup
+ path: fms_connection
+ analyzers:
+ connection_error:
+ type: diagnostic_aggregator/GenericAnalyzer
+ path: connection_error
+ contains: ["edge_core_internet_connection"]
+ timeout: 10.0
diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml
index 6a763eace4..a5689f4ccf 100644
--- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml
+++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml
@@ -17,30 +17,42 @@
ros__parameters:
required_modules:
autonomous_driving:
+ # Control (from control.param.yaml)
/autoware/control/autonomous_driving/node_alive_monitoring: default
- /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default
+ # /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default # temporarily until logic is improved
/autoware/control/control_command_gate/node_alive_monitoring: default
+ # Localization (from localization.param.yaml)
/autoware/localization/node_alive_monitoring: default
/autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" }
/autoware/localization/performance_monitoring/localization_accuracy: default
/autoware/localization/performance_monitoring/sensor_fusion_status: { sf_at: "error", lf_at: "none", spf_at: "none" }
+ # Map (from map.param.yaml)
/autoware/map/node_alive_monitoring: default
+ # Perception (from perception.param.yaml)
/autoware/perception/node_alive_monitoring: default
+ # Planning (from planning.param.yaml)
/autoware/planning/node_alive_monitoring: default
/autoware/planning/performance_monitoring/trajectory_validation: default
+ # Sensors (from sensor_kit.param.yaml)
# /autoware/sensing/node_alive_monitoring: default
+ /autoware/sensing/lidar/pandar/health_monitoring/connection: { sf_at: "none", lf_at: "none", spf_at: "error", auto_recovery: "true"}
+ /autoware/sensing/lidar/pandar/health_monitoring/temperature: { sf_at: "warn", lf_at: "error", spf_at: "none", auto_recovery: "true"}
+ /autoware/sensing/lidar/pandar/health_monitoring/ptp: { sf_at: "none", lf_at: "none", spf_at: "warn", auto_recovery: "true"}
+ # System (from system.param.yaml in universe and system.param.yaml in system_launch)
/autoware/system/node_alive_monitoring: default
/autoware/system/emergency_stop_operation: default
/autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" }
- /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "error", spf_at: "none" }
+ /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "none", spf_at: "none" }
/autoware/system/duplicated_node_checker: default
+ /autoware/system/fms_connection: { sf_at: "warn", lf_at: "none", spf_at: "none" }
+ # Vehicle (from vehicle.param.yaml in universe and vehicle.param.yaml in system_launch)
/autoware/vehicle/node_alive_monitoring: default
external_control:
diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml
index 3fd6264376..38dec9259a 100644
--- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml
+++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml
@@ -18,7 +18,7 @@
required_modules:
autonomous_driving:
/autoware/control/autonomous_driving/node_alive_monitoring: default
- /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default
+ # /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default # temporarily until logic is improved
/autoware/control/autonomous_driving/performance_monitoring/trajectory_deviation: default
/autoware/control/control_command_gate/node_alive_monitoring: default
diff --git a/autoware_launch/config/system/system_monitor/net_monitor.param.yaml b/autoware_launch/config/system/system_monitor/net_monitor.param.yaml
index d72b8d1334..adcae5a458 100644
--- a/autoware_launch/config/system/system_monitor/net_monitor.param.yaml
+++ b/autoware_launch/config/system/system_monitor/net_monitor.param.yaml
@@ -1,9 +1,9 @@
/**:
ros__parameters:
- devices: ["*"]
- traffic_reader_port: 7636
- monitor_program: "greengrass"
- crc_error_check_duration: 1
- crc_error_count_threshold: 1
- reassembles_failed_check_duration: 1
- reassembles_failed_check_count: 1
+ devices: ["enp2s0f1"]
+ traffic_reader_port: 7636
+ monitor_program: "greengrass"
+ crc_error_check_duration: 1
+ crc_error_count_threshold: 1
+ reassembles_failed_check_duration: 1
+ reassembles_failed_check_count: 1
diff --git a/autoware_launch/config/system/system_monitor/process_monitor.param.yaml b/autoware_launch/config/system/system_monitor/process_monitor.param.yaml
index 3d6d82fae5..64303dd472 100644
--- a/autoware_launch/config/system/system_monitor/process_monitor.param.yaml
+++ b/autoware_launch/config/system/system_monitor/process_monitor.param.yaml
@@ -1,3 +1,3 @@
/**:
ros__parameters:
- num_of_procs: 5
+ num_of_procs: 40
diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml
index 80822d0146..990ff17d13 100644
--- a/autoware_launch/launch/autoware.launch.xml
+++ b/autoware_launch/launch/autoware.launch.xml
@@ -22,6 +22,7 @@
+
@@ -38,12 +39,13 @@
-
+
-
+
+
@@ -116,6 +118,15 @@
+
+
+
+
+
+
+
+
+
-
+
-
+
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index 49156fba51..7fb68a02f5 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -21,6 +21,14 @@
+
+
+
+
+
+
+
+
-
+
+
+
+
+
diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml
index a2b66e91ed..c0a8cea41b 100644
--- a/autoware_launch/launch/logging_simulator.launch.xml
+++ b/autoware_launch/launch/logging_simulator.launch.xml
@@ -34,7 +34,9 @@
-
+
+
+
@@ -70,6 +72,10 @@
+
+
+
+
diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml
index 28a0f0e347..4430e8a0f8 100644
--- a/autoware_launch/launch/planning_simulator.launch.xml
+++ b/autoware_launch/launch/planning_simulator.launch.xml
@@ -63,6 +63,8 @@
+
+
diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz
index bc22eadb70..a8329b1e5c 100644
--- a/autoware_launch/rviz/autoware.rviz
+++ b/autoware_launch/rviz/autoware.rviz
@@ -2250,7 +2250,7 @@ Visualization Manager:
Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/slow_down/virtual_wall
Value: true
- Class: rviz_default_plugins/MarkerArray
- Enabled: true
+ Enabled: false
Name: DebugMarker
Namespaces:
{}
@@ -2261,7 +2261,7 @@ Visualization Manager:
Reliability Policy: Reliable
Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/marker
Value: true
- Enabled: false
+ Enabled: true
Name: ObstacleCruise
- Class: rviz_default_plugins/MarkerArray
Enabled: false