diff --git a/autoware_launch/config/control/control_validator/control_validator.param.yaml b/autoware_launch/config/control/control_validator/control_validator.param.yaml
new file mode 100644
index 0000000000..c51cbafba2
--- /dev/null
+++ b/autoware_launch/config/control/control_validator/control_validator.param.yaml
@@ -0,0 +1,14 @@
+/**:
+ ros__parameters:
+
+ publish_diag: false # if true, diagnostic msg is published
+
+ # If the number of consecutive invalid predicted_path exceeds this threshold, the Diag will be set to ERROR.
+ # (For example, threshold = 1 means, even if the predicted_path is invalid, Diag will not be ERROR if
+ # the next predicted_path is valid.)
+ diag_error_count_threshold: 0
+
+ display_on_terminal: false # show error msg on terminal
+
+ thresholds:
+ max_distance_deviation: 1.0
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 59e25cbc5d..2d044e7cfd 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
@@ -1,5 +1,10 @@
/**:
ros__parameters:
+ # Enable feature
+ will_out_of_lane_checker: true
+ out_of_lane_checker: true
+ boundary_departure_checker: false
+
# Node
update_rate: 10.0
visualize_lanelet: false
@@ -7,6 +12,7 @@
include_left_lanes: false
include_opposite_lanes: false
include_conflicting_lanes: false
+ boundary_types_to_detect: [road_border]
# Core
footprint_margin_scale: 1.0
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 a86443f5ca..a4e8ab2c83 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
@@ -2,6 +2,10 @@
ros__parameters:
transition_timeout: 10.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
+
check_engage_condition: false # 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
diff --git a/autoware_launch/config/control/predicted_path_checker/predicted_path_checker.param.yaml b/autoware_launch/config/control/predicted_path_checker/predicted_path_checker.param.yaml
new file mode 100644
index 0000000000..780d86b5e9
--- /dev/null
+++ b/autoware_launch/config/control/predicted_path_checker/predicted_path_checker.param.yaml
@@ -0,0 +1,22 @@
+/**:
+ ros__parameters:
+ # Node
+ update_rate: 10.0
+ delay_time: 0.17
+ max_deceleration: 1.5
+ resample_interval: 0.5
+ stop_margin: 0.5 # [m]
+ ego_nearest_dist_threshold: 3.0 # [m]
+ ego_nearest_yaw_threshold: 1.046 # [rad] = 60 [deg]
+ min_trajectory_check_length: 1.5 # [m]
+ trajectory_check_time: 3.0
+ distinct_point_distance_threshold: 0.3
+ distinct_point_yaw_threshold: 5.0 # [deg]
+ filtering_distance_threshold: 1.5 # [m]
+ use_object_prediction: true
+
+ collision_checker_params:
+ width_margin: 0.2
+ chattering_threshold: 0.2
+ z_axis_filtering_buffer: 0.3
+ enable_z_axis_obstacle_filtering: false
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 522cc3a1ca..191e894622 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
@@ -3,7 +3,9 @@
update_rate: 10.0
system_emergency_heartbeat_timeout: 0.5
use_emergency_handling: false
+ check_external_emergency_heartbeat: false
use_start_request: false
+ enable_cmd_limit_filter: true
external_emergency_stop_heartbeat_timeout: 0.0
stop_hold_acceleration: -1.5
emergency_acceleration: -2.4
@@ -12,15 +14,21 @@
stop_check_duration: 1.0
nominal:
vel_lim: 25.0
- lon_acc_lim: 5.0
- lon_jerk_lim: 5.0
- lat_acc_lim: 5.0
- lat_jerk_lim: 5.0
- actual_steer_diff_lim: 1.0
+ reference_speed_points: [20.0, 30.0]
+ steer_lim: [1.0, 0.8]
+ steer_rate_lim: [1.0, 0.8]
+ lon_acc_lim: [5.0, 4.0]
+ lon_jerk_lim: [5.0, 4.0]
+ lat_acc_lim: [5.0, 4.0]
+ lat_jerk_lim: [7.0, 6.0]
+ actual_steer_diff_lim: [1.0, 0.8]
on_transition:
vel_lim: 50.0
- lon_acc_lim: 1.0
- lon_jerk_lim: 0.5
- lat_acc_lim: 2.0
- lat_jerk_lim: 7.0
- actual_steer_diff_lim: 1.0
+ reference_speed_points: [20.0, 30.0]
+ steer_lim: [1.0, 0.8]
+ steer_rate_lim: [1.0, 0.8]
+ lon_acc_lim: [1.0, 0.9]
+ lon_jerk_lim: [0.5, 0.4]
+ lat_acc_lim: [2.0, 1.8]
+ lat_jerk_lim: [7.0, 6.0]
+ actual_steer_diff_lim: [1.0, 0.8]
diff --git a/autoware_launch/config/localization/ekf_localizer.param.yaml b/autoware_launch/config/localization/ekf_localizer.param.yaml
index 322325d239..667217d259 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: true
predict_frequency: 50.0
tf_rate: 50.0
extend_state_step: 50
@@ -21,3 +21,12 @@
proc_stddev_yaw_c: 0.005
proc_stddev_vx_c: 10.0
proc_stddev_wz_c: 5.0
+
+ # for diagnostics
+ pose_no_update_count_threshold_warn: 50
+ pose_no_update_count_threshold_error: 250
+ twist_no_update_count_threshold_warn: 50
+ 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]
diff --git a/autoware_launch/config/localization/localization_error_monitor.param.yaml b/autoware_launch/config/localization/localization_error_monitor.param.yaml
index 026daf0532..def5c80164 100644
--- a/autoware_launch/config/localization/localization_error_monitor.param.yaml
+++ b/autoware_launch/config/localization/localization_error_monitor.param.yaml
@@ -1,7 +1,7 @@
/**:
ros__parameters:
scale: 3.0
- error_ellipse_size: 1.0
- warn_ellipse_size: 0.8
+ error_ellipse_size: 1.5
+ warn_ellipse_size: 1.2
error_ellipse_size_lateral_direction: 0.3
- warn_ellipse_size_lateral_direction: 0.2
+ warn_ellipse_size_lateral_direction: 0.25
diff --git a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml
index a62a67716f..b1a1b163dd 100644
--- a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml
+++ b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml
@@ -6,6 +6,12 @@
# Vehicle reference frame
base_frame: "base_link"
+ # NDT reference frame
+ ndt_base_frame: "ndt_base_link"
+
+ # map frame
+ map_frame: "map"
+
# Subscriber queue size
input_sensor_points_queue_size: 1
@@ -35,7 +41,15 @@
converged_param_nearest_voxel_transformation_likelihood: 2.3
# The number of particles to estimate initial pose
- initial_estimate_particles_num: 100
+ initial_estimate_particles_num: 200
+
+ # The number of initial random trials in the TPE (Tree-Structured Parzen Estimator).
+ # This value should be equal to or less than 'initial_estimate_particles_num' and more than 0.
+ # If it is equal to 'initial_estimate_particles_num', the search will be the same as a full random search.
+ n_startup_trials: 20
+
+ # Tolerance of timestamp difference between current time and sensor pointcloud. [sec]
+ lidar_topic_timeout_sec: 1.0
# Tolerance of timestamp difference between initial_pose and sensor pointcloud. [sec]
initial_pose_timeout_sec: 1.0
@@ -43,10 +57,6 @@
# Tolerance of distance difference between two initial poses used for linear interpolation. [m]
initial_pose_distance_tolerance_m: 10.0
- # neighborhood search method
- # 0=KDTREE, 1=DIRECT26, 2=DIRECT7, 3=DIRECT1
- neighborhood_search_method: 0
-
# Number of threads used for parallel computing
num_threads: 4
@@ -82,8 +92,12 @@
# Radius of input LiDAR range (used for diagnostics of dynamic map loading)
lidar_radius: 100.0
+ # cspell: ignore degrounded
# A flag for using scan matching score based on de-grounded LiDAR scan
estimate_scores_for_degrounded_scan: false
# If lidar_point.z - base_link.z <= this threshold , the point will be removed
z_margin_for_ground_removal: 0.8
+
+ # The execution time which means probably NDT cannot matches scans properly. [ms]
+ critical_upper_bound_exe_time_ms: 100
diff --git a/autoware_launch/config/map/lanelet2_map_loader.param.yaml b/autoware_launch/config/map/lanelet2_map_loader.param.yaml
index 9abbaf2901..24d2b0e8ed 100755
--- a/autoware_launch/config/map/lanelet2_map_loader.param.yaml
+++ b/autoware_launch/config/map/lanelet2_map_loader.param.yaml
@@ -1,7 +1,3 @@
/**:
ros__parameters:
- lanelet2_map_projector_type: MGRS # Options: MGRS, UTM, local
- latitude: 40.81187906 # Latitude of map_origin, using in UTM
- longitude: 29.35810110 # Longitude of map_origin, using in UTM
-
center_line_resolution: 5.0 # [m]
diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml
deleted file mode 100644
index 3dd303464a..0000000000
--- a/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml
+++ /dev/null
@@ -1,20 +0,0 @@
-/**:
- ros__parameters:
-
- # distance threshold for compare compare
- distance_threshold: 0.5
-
- # publish voxelized map pointcloud for debug
- publish_debug_pcd: False
-
- # use dynamic map loading
- use_dynamic_map_loading: True
-
- # time interval to check dynamic map loading
- timer_interval_ms: 100
-
- # distance threshold for dynamic map update
- map_update_distance_threshold: 10.0
-
- # radius map for dynamic map loading
- map_loader_radius: 150.0
diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml
deleted file mode 100644
index 1962fba1f3..0000000000
--- a/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml
+++ /dev/null
@@ -1,8 +0,0 @@
-/**:
- ros__parameters:
- input_frame: base_link
- output_frame: base_link
- voxel_size_x: 0.3
- voxel_size_y: 0.3
- voxel_size_z: 100.0
- voxel_points_threshold: 3
diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml
deleted file mode 100644
index 3ff32bfbb7..0000000000
--- a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml
+++ /dev/null
@@ -1,7 +0,0 @@
-/**:
- ros__parameters:
- input_frame: base_link
- output_frame: base_link
- voxel_size_x: 0.15
- voxel_size_y: 0.15
- voxel_size_z: 0.15
diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml
index 2f3de2b789..26b027f007 100644
--- a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml
@@ -7,9 +7,11 @@
max_cluster_size: 3000
use_height: false
input_frame: "base_link"
- max_x: 70.0
- min_x: -70.0
- max_y: 70.0
- min_y: -70.0
- max_z: 4.5
- min_z: -4.5
+
+ # low height crop box filter param
+ max_x: 200.0
+ min_x: -200.0
+ max_y: 200.0
+ min_y: -200.0
+ max_z: 2.0
+ min_z: -10.0
diff --git a/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml
new file mode 100644
index 0000000000..22999b411f
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml
@@ -0,0 +1,13 @@
+/**:
+ ros__parameters:
+ min_points_num:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [10, 10, 10, 10, 10,10, 10, 10]
+
+ max_points_num:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [10, 10, 10, 10, 10,10, 10, 10]
+
+ min_points_and_distance_ratio:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [800.0, 880.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0]
diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml
index 56346b5a3e..e1be5426cb 100755
--- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml
@@ -1,15 +1,16 @@
/**:
ros__parameters:
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
- point_feature_size: 9 # x, y, z, time-lag and car, pedestrian, bicycle
+ paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"]
+ point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle
max_voxel_size: 40000
- point_cloud_range: [-102.4, -102.4, -4.0, 102.4, 102.4, 6.0]
- voxel_size: [0.32, 0.32, 10.0]
+ point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0]
+ voxel_size: [0.32, 0.32, 8.0]
downsample_factor: 1
- encoder_in_feature_size: 14
+ encoder_in_feature_size: 12
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
# post-process params
- circle_nms_dist_threshold: 0.5
+ circle_nms_dist_threshold: 0.3
iou_nms_target_class_names: ["CAR"]
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
diff --git a/autoware_launch/config/perception/object_recognition/detection/object_filter/radar_lanelet_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_filter/radar_lanelet_filter.param.yaml
new file mode 100644
index 0000000000..62051e1c5e
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/object_filter/radar_lanelet_filter.param.yaml
@@ -0,0 +1,11 @@
+/**:
+ ros__parameters:
+ filter_target_label:
+ UNKNOWN : true
+ CAR : true
+ TRUCK : true
+ BUS : true
+ TRAILER : true
+ MOTORCYCLE : true
+ BICYCLE : true
+ PEDESTRIAN : true
diff --git a/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml
index 0423217582..62b3074c15 100644
--- a/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml
@@ -1,7 +1,5 @@
/**:
ros__parameters:
- # use downsample filter before compare map
- use_down_sample_filter: False
# voxel size for downsample filter
down_sample_voxel_size: 0.1
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 eae747ce38..31fae9c811 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,17 +1,21 @@
/**:
ros__parameters:
enable_delay_compensation: true
- prediction_time_horizon: 7.8 #[s]
+ prediction_time_horizon: 10.0 #[s]
prediction_sampling_delta_time: 0.5 #[s]
min_velocity_for_map_based_prediction: 1.39 #[m/s]
min_crosswalk_user_velocity: 1.39 #[m/s]
+ max_crosswalk_user_delta_yaw_threshold_for_lanelet: 0.785 #[m/s]
dist_threshold_for_searching_lanelet: 3.0 #[m]
delta_yaw_threshold_for_searching_lanelet: 0.785 #[rad]
sigma_lateral_offset: 0.5 #[m]
sigma_yaw_angle_deg: 5.0 #[angle degree]
object_buffer_time_length: 2.0 #[s]
history_time_length: 1.0 #[s]
+ # parameter for shoulder lane prediction
+ prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8
+ # parameters for lc prediction
lane_change_detection:
method: "lat_diff_distance" # choose from "lat_diff_distance" or "time_to_change_lane"
time_to_change_lane:
diff --git a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml
index 69af202e7a..13f2220655 100644
--- a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml
@@ -30,9 +30,9 @@
36.00, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #TRUCK
60.00, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #BUS
60.00, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #TRAILER
- 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #MOTORBIKE
- 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #BICYCLE
- 2.00, 10000.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00] #PEDESTRIAN
+ 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.50, #MOTORBIKE
+ 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.50, #BICYCLE
+ 2.00, 10000.00, 10000.00, 10000.00, 10000.00, 2.00, 2.00, 1.50] #PEDESTRIAN
min_area_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN
diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/radar_object_tracker.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/radar_object_tracker.param.yaml
new file mode 100644
index 0000000000..f80adffb41
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/radar_object_tracker.param.yaml
@@ -0,0 +1,27 @@
+# general parameters for radar_object_tracker node
+/**:
+ ros__parameters:
+ # basic settings
+ world_frame_id: "map"
+ tracker_lifetime: 1.0 # [sec]
+ # if empty, use default config declared in this package
+ tracking_config_directory: ""
+
+ # delay compensate parameters
+ publish_rate: 10.0
+ enable_delay_compensation: false
+
+ # logging
+ enable_logging: false
+ logging_file_path: "/tmp/association_log.json"
+
+ # filtering
+ ## 1. distance based filtering: remove closer objects than this threshold
+ use_distance_based_noise_filtering: true
+ minimum_range_threshold: 70.0 # [m]
+
+ ## 2. lanelet map based filtering
+ use_map_based_noise_filtering: true
+ max_distance_from_lane: 5.0 # [m]
+ max_angle_diff_from_lane: 0.785398 # [rad] (45 deg)
+ max_lateral_velocity: 5.0 # [m/s]
diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/linear_motion_tracker.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/linear_motion_tracker.yaml
new file mode 100644
index 0000000000..71367f4575
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/linear_motion_tracker.yaml
@@ -0,0 +1,32 @@
+default:
+ # This file defines the parameters for the linear motion tracker.
+ # All this parameter coordinate is assumed to be in the vehicle coordinate system.
+ # So, the x axis is pointing to the front of the vehicle, y axis is pointing to the left of the vehicle.
+ ekf_params:
+ # random walk noise is used to model the acceleration noise
+ process_noise_std: # [m/s^2]
+ ax: 0.98 # assume 0.1G acceleration noise
+ ay: 0.98
+ vx: 0.1 # assume 0.1m/s velocity noise
+ vy: 0.1
+ x: 1.0 # assume 1m position noise
+ y: 1.0
+ measurement_noise_std:
+ x: 0.6 # [m]
+ y: 0.9 # [m]
+ vx: 0.4 # [m/s]
+ vy: 1 # [m/s]
+ initial_covariance_std:
+ x: 3.0 # [m]
+ y: 6.0 # [m]
+ vx: 1.0 # [m/s]
+ vy: 5.0 # [m/s]
+ ax: 0.5 # [m/s^2]
+ ay: 1.0 # [m/s^2]
+ # output limitation
+ limit:
+ max_speed: 80.0 # [m/s]
+ # low pass filter is used to smooth the yaw and shape estimation
+ low_pass_filter:
+ time_constant: 1.0 # [s]
+ sampling_time: 0.1 # [s]
diff --git a/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/data_association_matrix.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/data_association_matrix.param.yaml
new file mode 100644
index 0000000000..702809b3ce
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/data_association_matrix.param.yaml
@@ -0,0 +1,168 @@
+/**:
+ ros__parameters:
+ lidar-lidar:
+ can_assign_matrix:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
+ [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
+ 0, 1, 1, 1, 1, 0, 0, 0, #CAR
+ 0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
+ 0, 1, 1, 1, 1, 0, 0, 0, #BUS
+ 0, 1, 1, 1, 1, 0, 0, 0, #TRAILER
+ 0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE
+ 0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE
+ 0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN
+
+ max_dist_matrix:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [4.0, 4.0, 5.0, 5.0, 5.0, 2.0, 2.0, 2.0, #UNKNOWN
+ 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR
+ 5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK
+ 5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS
+ 5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER
+ 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #MOTORBIKE
+ 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #BICYCLE
+ 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN
+
+ max_rad_matrix: # If value is greater than pi, it will be ignored.
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN
+ [3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER
+ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE
+ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE
+ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN
+
+ max_velocity_diff_matrix: # Ignored when value is larger than 100.0
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #UNKNOWN
+ 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #CAR
+ 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRUCK
+ 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #BUS
+ 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRAILER
+ 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #MOTORBIKE
+ 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #BICYCLE
+ 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0] #PEDESTRIAN
+
+ min_iou_matrix: # If value is negative, it will be ignored.
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN
+ 0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR
+ 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK
+ 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS
+ 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER
+ 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE
+ 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE
+ 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] #PEDESTRIAN
+
+ lidar-radar:
+ can_assign_matrix:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
+ [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
+ 0, 1, 1, 1, 1, 0, 0, 0, #CAR
+ 0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
+ 0, 1, 1, 1, 1, 0, 0, 0, #BUS
+ 0, 1, 1, 1, 1, 0, 0, 0, #TRAILER
+ 0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE
+ 0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE
+ 0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN
+
+ max_dist_matrix:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [4.0, 4.0, 5.0, 5.0, 5.0, 3.5, 3.5, 3.5, #UNKNOWN
+ 4.0, 5.5, 6.0, 6.0, 6.0, 1.0, 1.0, 1.0, #CAR
+ 5.0, 6.0, 6.5, 6.5, 6.5, 1.0, 1.0, 1.0, #TRUCK
+ 5.0, 6.0, 6.5, 6.5, 6.5, 1.0, 1.0, 1.0, #BUS
+ 5.0, 6.0, 6.5, 6.5, 6.5, 1.0, 1.0, 1.0, #TRAILER
+ 3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #MOTORBIKE
+ 3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #BICYCLE
+ 3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.5] #PEDESTRIAN
+
+ max_rad_matrix: # If value is greater than pi, it will be ignored.
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN
+ [3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER
+ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE
+ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE
+ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN
+
+ max_velocity_diff_matrix: # Ignored when value is larger than 100.0
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #UNKNOWN
+ 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #CAR
+ 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRUCK
+ 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #BUS
+ 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRAILER
+ 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #MOTORBIKE
+ 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #BICYCLE
+ 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0] #PEDESTRIAN
+
+ min_iou_matrix: # set all value to 0.0 to disable this constraint
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #UNKNOWN
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #CAR
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #TRUCK
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #BUS
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #TRAILER
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #MOTORBIKE
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #BICYCLE
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] #PEDESTRIAN
+
+ radar-radar:
+ can_assign_matrix:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
+ [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
+ 0, 1, 1, 1, 1, 0, 0, 0, #CAR
+ 0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
+ 0, 1, 1, 1, 1, 0, 0, 0, #BUS
+ 0, 1, 1, 1, 1, 0, 0, 0, #TRAILER
+ 0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE
+ 0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE
+ 0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN
+
+ max_dist_matrix:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [4.0, 4.0, 5.0, 5.0, 5.0, 3.5, 3.5, 3.5, #UNKNOWN
+ 4.0, 7.0, 7.5, 7.5, 7.5, 1.0, 1.0, 1.0, #CAR
+ 5.0, 7.5, 7.5, 7.5, 7.5, 1.0, 1.0, 1.0, #TRUCK
+ 5.0, 7.5, 7.5, 7.5, 7.5, 1.0, 1.0, 1.0, #BUS
+ 5.0, 7.5, 7.5, 7.5, 7.5, 1.0, 1.0, 1.0, #TRAILER
+ 3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #MOTORBIKE
+ 3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #BICYCLE
+ 3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.5] #PEDESTRIAN
+ max_rad_matrix: # If value is greater than pi, it will be ignored.
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN
+ [3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS
+ 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER
+ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE
+ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE
+ 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN
+
+ max_velocity_diff_matrix: # Ignored when value is larger than 100.0
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #UNKNOWN
+ 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #CAR
+ 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRUCK
+ 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #BUS
+ 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRAILER
+ 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #MOTORBIKE
+ 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #BICYCLE
+ 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0] #PEDESTRIAN
+
+ min_iou_matrix: # set all value to 0.0 to disable this constraint
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #UNKNOWN
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #CAR
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #TRUCK
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #BUS
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #TRAILER
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #MOTORBIKE
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #BICYCLE
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] #PEDESTRIAN
diff --git a/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger.param.yaml
new file mode 100644
index 0000000000..13369d5422
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger.param.yaml
@@ -0,0 +1,26 @@
+# Node parameters
+/**:
+ ros__parameters:
+ base_link_frame_id: "base_link"
+ time_sync_threshold: 0.999
+ sub_object_timeout_sec: 0.8
+ publish_interpolated_sub_objects: true #for debug
+
+ # choose the input sensor type for each object type
+ # "lidar", "radar", "camera" are available
+ main_sensor_type: "lidar"
+ sub_sensor_type: "radar"
+
+ # tracker settings
+ tracker_state_parameter:
+ remove_probability_threshold: 0.3
+ publish_probability_threshold: 0.5
+ default_lidar_existence_probability: 0.7
+ default_radar_existence_probability: 0.6
+ default_camera_existence_probability: 0.5
+ decay_rate: 0.1
+ max_dt: 1.0
+
+ # logging
+ enable_logging: false
+ log_file_path: "/tmp/decorative_tracker_merger.log"
diff --git a/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger_policy.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger_policy.param.yaml
new file mode 100644
index 0000000000..0b98e1b202
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger_policy.param.yaml
@@ -0,0 +1,16 @@
+# Merger policy for decorative tracker merger node
+# decorative tracker merger works by merging the sub-object trackers into a main object tracker result
+# There are 3 merger policy:
+# 1. "skip": skip the sub-object tracker result
+# 2. "overwrite": overwrite the main object tracker result with sub-object tracker result
+# 3. "fusion": merge the main object tracker result with sub-object tracker result by using covariance based fusion
+/**:
+ ros__parameters:
+ kinematics_to_be_merged: "velocity" # currently only support "velocity"
+
+ # choose the merger policy for each object type
+ # : "skip", "overwrite", "fusion"
+ kinematics_merge_policy: "overwrite"
+ classification_merge_policy: "skip"
+ existence_prob_merge_policy: "skip"
+ shape_merge_policy: "skip"
diff --git a/autoware_launch/config/planning/mission_planning/mission_planner/mission_planner.param.yaml b/autoware_launch/config/planning/mission_planning/mission_planner/mission_planner.param.yaml
index d596eb9816..9b7dcffbc6 100644
--- a/autoware_launch/config/planning/mission_planning/mission_planner/mission_planner.param.yaml
+++ b/autoware_launch/config/planning/mission_planning/mission_planner/mission_planner.param.yaml
@@ -8,3 +8,5 @@
enable_correct_goal_pose: false
reroute_time_threshold: 10.0
minimum_reroute_length: 30.0
+ consider_no_drivable_lanes: false # This flag is for considering no_drivable_lanes in planning or not.
+ check_footprint_inside_lanes: true
diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml
index a6906b7117..f74ca045f5 100644
--- a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml
@@ -1,7 +1,7 @@
/**:
ros__parameters:
- jerk_weight: 0.1 # weight for "smoothness" cost for jerk
- over_v_weight: 10000.0 # weight for "over speed limit" cost
- over_a_weight: 500.0 # weight for "over accel limit" cost
- over_j_weight: 200.0 # weight for "over jerk limit" cost
+ jerk_weight: 10.0 # weight for "smoothness" cost for jerk
+ over_v_weight: 100000.0 # weight for "over speed limit" cost
+ over_a_weight: 5000.0 # weight for "over accel limit" cost
+ over_j_weight: 2000.0 # weight for "over jerk limit" cost
jerk_filter_ds: 0.1 # resampling ds for jerk filter
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 868b1bd15c..235c76a5c1 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
@@ -7,12 +7,21 @@
# external velocity limit parameter
margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m]
- # curve parameters
+ # -- curve parameters --
+ # common parameters
+ 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]
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
min_decel_for_lateral_acc_lim_filter: -2.5 # deceleration limit applied in the lateral acceleration filter to avoid sudden braking [m/ss]
+ # steering angle rate limit parameters
+ enable_steering_rate_limit: true # To toggle the steer rate filter on and off. You can switch it dynamically at runtime.
+ max_steering_angle_rate: 40.0 # maximum steering angle rate [degree/s]
+ resample_ds: 0.1 # distance between trajectory points [m]
+ curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m]
# engage & replan parameters
replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s]
@@ -48,12 +57,6 @@
post_sparse_resample_dt: 0.1 # resample time interval for sparse sampling [s]
post_sparse_min_interval_distance: 1.0 # minimum points-interval length for sparse sampling [m]
- # steering angle rate limit parameters
- max_steering_angle_rate: 40.0 # maximum steering angle rate [degree/s]
- resample_ds: 0.1 # distance between trajectory points [m]
- curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m]
- curvature_calculation_distance: 1.0 # distance of points while curvature is calculating [m]
-
# system
over_stop_velocity_warn_thr: 1.389 # used to check if the optimization exceeds the input velocity on the stop point
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 cff48985a2..fe9c37d200 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
@@ -4,17 +4,15 @@
avoidance:
resample_interval_for_planning: 0.3 # [m]
resample_interval_for_output: 4.0 # [m]
- detection_area_right_expand_dist: 0.0 # [m]
- detection_area_left_expand_dist: 1.0 # [m]
drivable_area_right_bound_offset: 0.0 # [m]
drivable_area_left_bound_offset: 0.0 # [m]
# avoidance module common setting
enable_bound_clipping: false
- enable_update_path_when_object_is_gone: false
enable_force_avoidance_for_stopped_vehicle: false
enable_yield_maneuver: true
enable_yield_maneuver_during_shifting: false
+ enable_cancel_maneuver: true
disable_path_update: false
# drivable area setting
@@ -120,8 +118,6 @@
object_ignore_section_crosswalk_in_front_distance: 30.0 # [m]
object_ignore_section_crosswalk_behind_distance: 30.0 # [m]
# detection range
- object_check_forward_distance: 150.0 # [m]
- object_check_backward_distance: 10.0 # [m]
object_check_goal_distance: 20.0 # [m]
# filtering parking objects
threshold_distance_object_is_on_center: 1.0 # [m]
@@ -130,6 +126,13 @@
# lost object compensation
object_last_seen_threshold: 2.0
+ # detection area generation parameters
+ detection_area:
+ static: false # [-]
+ min_forward_distance: 50.0 # [m]
+ max_forward_distance: 150.0 # [m]
+ backward_distance: 10.0 # [m]
+
# For safety check
safety_check:
# safety check configuration
@@ -141,11 +144,24 @@
check_other_object: true # [-]
# collision check parameters
check_all_predicted_path: false # [-]
- time_resolution: 0.5 # [s]
- time_horizon: 10.0 # [s]
safety_check_backward_distance: 100.0 # [m]
- safety_check_hysteresis_factor: 2.0 # [-]
- safety_check_ego_offset: 1.0 # [m]
+ hysteresis_factor_expand_rate: 1.5 # [-]
+ hysteresis_factor_safe_count: 10 # [-]
+ # predicted path parameters
+ min_velocity: 1.38 # [m/s]
+ max_velocity: 50.0 # [m/s]
+ time_resolution: 0.5 # [s]
+ time_horizon_for_front_object: 3.0 # [s]
+ time_horizon_for_rear_object: 10.0 # [s]
+ delay_until_departure: 0.0 # [s]
+ # rss parameters
+ expected_front_deceleration: -1.0 # [m/ss]
+ 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]
+ longitudinal_distance_min_threshold: 3.0 # [m]
+ longitudinal_velocity_delta_time: 0.8 # [s]
# For avoidance maneuver
avoidance:
@@ -154,9 +170,11 @@
lateral_execution_threshold: 0.09 # [m]
lateral_small_shift_threshold: 0.101 # [m]
lateral_avoid_check_threshold: 0.1 # [m]
- road_shoulder_safety_margin: 0.3 # [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]
# avoidance distance parameters
longitudinal:
prepare_time: 2.0 # [s]
@@ -175,10 +193,23 @@
max_distance: 20.0 # [m]
stop_buffer: 1.0 # [m]
- constraints:
- # vehicle slows down under longitudinal constraints
- use_constraints_for_decel: true # [-]
+ policy:
+ # policy for vehicle slow down behavior. select "best_effort" or "reliable".
+ # "best_effort": slow down deceleration & jerk are limited by constraints.
+ # but there is a possibility that the vehicle can't stop in front of the vehicle.
+ # "reliable": insert stop or slow down point with ignoring decel/jerk constraints.
+ # make it possible to increase chance to avoid but uncomfortable deceleration maybe happen.
+ deceleration: "best_effort" # [-]
+ # policy for avoidance lateral margin. select "best_effort" or "reliable".
+ # "best_effort": output avoidance path with shorten lateral margin when there is no enough longitudinal
+ # margin to avoid.
+ # "reliable": module output avoidance path with safe (rtc cooperate) state only when the vehicle can avoid
+ # with expected lateral margin.
+ lateral_margin: "best_effort" # [-]
+ # if true, module doesn't wait deceleration and outputs avoidance path by best effort margin.
+ use_shorten_margin_immediately: true # [-]
+ constraints:
# lateral constraints
lateral:
velocity: [1.0, 1.38, 11.1] # [m/s]
@@ -194,12 +225,6 @@
max_jerk: 1.0 # [m/sss]
max_acceleration: 1.0 # [m/ss]
- target_velocity_matrix:
- col_size: 2
- matrix:
- [2.78, 13.9, # velocity [m/s]
- 0.50, 1.00] # margin [m]
-
shift_line_pipeline:
trim:
quantize_filter_threshold: 0.1
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml
index aa56edee2f..5de4c0d27b 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml
@@ -29,19 +29,6 @@
visualize_maximum_drivable_area: true
- lateral_distance_max_threshold: 1.7
- longitudinal_distance_min_threshold: 3.0
- longitudinal_velocity_delta_time: 0.8
-
- expected_front_deceleration: -1.0
- expected_rear_deceleration: -1.0
-
- expected_front_deceleration_for_abort: -1.0
- expected_rear_deceleration_for_abort: -2.0
-
- rear_vehicle_reaction_time: 2.0
- rear_vehicle_safety_time_margin: 1.0
-
lane_following:
drivable_area_right_bound_offset: 0.0
drivable_area_left_bound_offset: 0.0
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 1609cdbc60..e1a0c7e38d 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
@@ -5,15 +5,19 @@
drivable_area_left_bound_offset: 0.0
drivable_area_types_to_skip: [road_border]
- # Dynamic expansion by projecting the ego footprint along the path
+ # Dynamic expansion by using the path curvature
dynamic_expansion:
enabled: false
+ print_runtime: false
+ max_expansion_distance: 0.0 # [m] maximum distance by which the drivable area can be expended (0.0 means no limit)
+ smoothing:
+ curvature_average_window: 3 # window size used for smoothing the curvatures using a moving window average
+ max_bound_rate: 1.0 # [m/m] maximum rate of change of the bound lateral distance over its arc length
+ extra_arc_length: 2.0 # [m] extra arc length where an expansion distance is initially applied
ego:
- extra_footprint_offset:
- front: 0.5 # [m] extra length to add to the front of the ego footprint
- rear: 0.5 # [m] extra length to add to the rear of the ego footprint
- left: 0.5 # [m] extra length to add to the left of the ego footprint
- right: 0.5 # [m] extra length to add to the rear of the ego footprint
+ extra_wheelbase: 0.0 # [m] extra length to add to the wheelbase
+ extra_front_overhang: 0.5 # [m] extra length to add to the front overhang
+ extra_width: 1.0 # [m] extra length to add to the width
dynamic_objects:
avoid: true # if true, the drivable area is not expanded in the predicted path of dynamic objects
extra_footprint_offset:
@@ -21,17 +25,12 @@
rear: 0.5 # [m] extra length to add to the rear of the dynamic object footprint
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
- expansion:
- method: polygon # method used to expand the drivable area. Either 'lanelet' or 'polygon'.
- # 'lanelet': add lanelets overlapped by the ego footprints
- # 'polygon': add polygons built around sections of the ego footprint that go out of the drivable area
- max_distance: 0.0 # [m] maximum distance by which the drivable area can be expended (0.0 means no limit)
- max_path_arc_length: 50.0 # [m] maximum arc length along the path where the ego footprint is projected (0.0 means no limit)
- extra_arc_length: 0.5 # [m] extra expansion arc length around an ego footprint
+ path_preprocessing:
+ max_arc_length: 50.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:
types: # linestring types in the lanelet maps that will not be crossed when expanding the drivable area
- road_border
+ - curbstone
distance: 0.0 # [m] distance to keep between the drivable area and the linestrings to avoid
- compensate:
- enable: true # if true, when the drivable area cannot be expanded in one direction to completely include the ego footprint, it is expanded in the opposite direction
- extra_distance: 3.0 # [m] extra distance to add to the compensation
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml
index 336879185f..bf9c815405 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml
@@ -2,7 +2,8 @@
ros__parameters:
dynamic_avoidance:
common:
- enable_debug_info: true
+ enable_debug_info: false
+ use_hatched_road_markings: true
# avoidance is performed for the object type with true
target_object:
@@ -15,9 +16,11 @@
motorcycle: true
pedestrian: false
+ max_obstacle_vel: 100.0 # [m/s]
min_obstacle_vel: 0.0 # [m/s]
successive_num_to_entry_dynamic_avoidance_condition: 5
+ successive_num_to_exit_dynamic_avoidance_condition: 1
min_obj_lat_offset_to_ego_path: 0.0 # [m]
max_obj_lat_offset_to_ego_path: 1.0 # [m]
@@ -26,26 +29,37 @@
min_time_to_start_cut_in: 1.0 # [s]
min_lon_offset_ego_to_object: 0.0 # [m]
+ cut_out_object:
+ max_time_from_outside_ego_path: 2.0 # [s]
+ min_object_lat_vel: 0.3 # [m/s]
+
crossing_object:
- min_object_vel: 1.0
- max_object_angle: 1.05
+ min_overtaking_object_vel: 1.0
+ max_overtaking_object_angle: 1.05
+ min_oncoming_object_vel: 0.0
+ max_oncoming_object_angle: 0.523
front_object:
max_object_angle: 0.785
drivable_area_generation:
- lat_offset_from_obstacle: 1.0 # [m]
+ object_path_base:
+ min_longitudinal_polygon_margin: 3.0 # [m]
+
+ lat_offset_from_obstacle: 0.8 # [m]
max_lat_offset_to_avoid: 0.5 # [m]
+ max_time_for_object_lat_shift: 0.0 # [s]
+ lpf_gain_for_lat_avoid_to_offset: 0.9 # [-]
# for same directional object
overtaking_object:
- max_time_to_collision: 10.0 # [s]
+ max_time_to_collision: 40.0 # [s]
start_duration_to_avoid: 2.0 # [s]
end_duration_to_avoid: 4.0 # [s]
duration_to_hold_avoidance: 3.0 # [s]
# for opposite directional object
oncoming_object:
- max_time_to_collision: 15.0 # [s]
+ max_time_to_collision: 40.0 # [s] This value should be the same as overtaking_object's one to suppress chattering of this value for parked vehicles
start_duration_to_avoid: 12.0 # [s]
end_duration_to_avoid: 0.0 # [s]
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 eaa103bff7..0f1b441bed 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
@@ -2,28 +2,32 @@
ros__parameters:
goal_planner:
# general params
- minimum_request_length: 100.0
th_arrived_distance: 1.0
th_stopped_velocity: 0.01
th_stopped_time: 2.0 # It must be greater than the state_machine's.
+ center_line_path_interval: 1.0
# goal search
goal_search:
- search_priority: "efficient_path" # "efficient_path" or "close_goal"
+ goal_priority: "minimum_weighted_distance" # "minimum_weighted_distance" or "minimum_longitudinal_distance"
+ minimum_weighted_distance:
+ lateral_weight: 40.0
+ prioritize_goals_before_objects: true
parking_policy: "left_side" # "left_side" or "right_side"
- forward_goal_search_length: 20.0
+ forward_goal_search_length: 40.0
backward_goal_search_length: 20.0
goal_search_interval: 2.0
longitudinal_margin: 3.0
- max_lateral_offset: 0.5
- lateral_offset_interval: 0.25
- ignore_distance_from_lane_start: 15.0
+ max_lateral_offset: 1.0
+ lateral_offset_interval: 0.5
+ ignore_distance_from_lane_start: 0.0
margin_from_boundary: 0.75
# occupancy grid map
occupancy_grid:
- use_occupancy_grid: true
- use_occupancy_grid_for_longitudinal_margin: false
+ use_occupancy_grid_for_goal_search: true
+ use_occupancy_grid_for_goal_longitudinal_margin: false
+ use_occupancy_grid_for_path_collision_check: false
occupancy_grid_collision_check_margin: 0.0
theta_size: 360
obstacle_threshold: 60
@@ -31,15 +35,20 @@
# object recognition
object_recognition:
use_object_recognition: true
- object_recognition_collision_check_margin: 1.0
+ object_recognition_collision_check_margin: 0.6 # this should be larger than `surround_check_distance` of surround_obstacle_checker
+ object_recognition_collision_check_max_extra_stopping_margin: 1.0
+ th_moving_object_velocity: 1.0
# pull over
pull_over:
+ minimum_request_length: 0.0
pull_over_velocity: 3.0
pull_over_minimum_velocity: 1.38
decide_path_distance: 10.0
maximum_deceleration: 1.0
maximum_jerk: 1.0
+ path_priority: "efficient_path" # "efficient_path" or "close_goal"
+ efficient_path_order: ["SHIFT", "ARC_FORWARD", "ARC_BACKWARD"] # only lane based pull over(exculde freespace parking)
# shift parking
shift_parking:
@@ -103,6 +112,69 @@
neighbor_radius: 8.0
margin: 1.0
+ stop_condition:
+ maximum_deceleration_for_stop: 1.0
+ maximum_jerk_for_stop: 1.0
+ path_safety_check:
+ # EgoPredictedPath
+ ego_predicted_path:
+ min_velocity: 1.0
+ acceleration: 1.0
+ max_velocity: 1.0
+ time_horizon_for_front_object: 10.0
+ time_horizon_for_rear_object: 10.0
+ time_resolution: 0.5
+ delay_until_departure: 1.0
+ # For target object filtering
+ target_filtering:
+ safety_check_time_horizon: 5.0
+ safety_check_time_resolution: 1.0
+ # detection range
+ object_check_forward_distance: 10.0
+ object_check_backward_distance: 100.0
+ ignore_object_velocity_threshold: 1.0
+ # ObjectTypesToCheck
+ object_types_to_check:
+ check_car: true
+ check_truck: true
+ check_bus: true
+ check_trailer: true
+ check_bicycle: true
+ check_motorcycle: true
+ check_pedestrian: true
+ check_unknown: false
+ # ObjectLaneConfiguration
+ object_lane_configuration:
+ check_current_lane: true
+ check_right_side_lane: true
+ check_left_side_lane: true
+ check_shoulder_lane: true
+ check_other_lane: false
+ include_opposite_lane: false
+ invert_opposite_lane: false
+ check_all_predicted_path: true
+ use_all_predicted_path: true
+ use_predicted_path_outside_lanelet: false
+
+ # For safety check
+ safety_check_params:
+ # safety check configuration
+ enable_safety_check: false # Don't set to true if auto_mode is enabled
+ # collision check parameters
+ check_all_predicted_path: true
+ publish_debug_marker: false
+ rss_params:
+ 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
+ # hysteresis factor to expand/shrink polygon with the value
+ hysteresis_factor_expand_rate: 1.0
+ # temporary
+ backward_path_length: 30.0
+ forward_path_length: 100.0
+
# debug
debug:
print_debug_info: false
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 1f075993aa..e09f6e479b 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
@@ -8,7 +8,6 @@
lane_change_finish_judge_buffer: 2.0 # [m]
lane_changing_lateral_jerk: 0.5 # [m/s3]
- lateral_acc_switching_velocity: 4.0 #[m/s]
minimum_lane_changing_velocity: 2.78 # [m/s]
prediction_time_resolution: 0.5 # [s]
@@ -27,6 +26,39 @@
min_longitudinal_acc: -1.0
max_longitudinal_acc: 1.0
+ # safety check
+ safety_check:
+ allow_loose_check_for_cancel: true
+ execution:
+ 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
+ cancel:
+ expected_front_deceleration: -1.0
+ expected_rear_deceleration: -2.0
+ rear_vehicle_reaction_time: 1.5
+ rear_vehicle_safety_time_margin: 0.8
+ 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]
+
# lateral acceleration map
lateral_acceleration:
velocity: [0.0, 4.0, 10.0]
@@ -51,6 +83,16 @@
check_objects_on_other_lanes: true
use_all_predicted_path: true
+ # lane change regulations
+ regulation:
+ crosswalk: false
+ intersection: false
+
+ # ego vehicle stuck detection
+ stuck_detection:
+ velocity: 0.5 # [m/s]
+ stop_time: 3.0 # [s]
+
# lane change cancel
cancel:
enable_on_prepare_phase: true
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 65582656b9..1fc83edd08 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
@@ -5,80 +5,90 @@
ros__parameters:
external_request_lane_change_left:
enable_module: false
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: true
- priority: 7
+ keep_last: false
+ priority: 6
max_module_size: 1
external_request_lane_change_right:
enable_module: false
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: true
- priority: 7
+ keep_last: false
+ priority: 6
max_module_size: 1
lane_change_left:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
- priority: 6
+ keep_last: false
+ priority: 5
max_module_size: 1
lane_change_right:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
- priority: 6
+ keep_last: false
+ priority: 5
max_module_size: 1
start_planner:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
+ keep_last: false
priority: 0
max_module_size: 1
side_shift:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
+ keep_last: false
priority: 2
max_module_size: 1
goal_planner:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
+ keep_last: true
priority: 1
max_module_size: 1
avoidance:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
- priority: 5
+ keep_last: false
+ priority: 4
max_module_size: 1
avoidance_by_lc:
enable_module: true
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
- priority: 4
+ keep_last: false
+ priority: 3
max_module_size: 1
dynamic_avoidance:
enable_module: false
- enable_rtc: true
+ enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
- priority: 3
+ keep_last: true
+ priority: 7
max_module_size: 1
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 5ae5c99ff8..1424b58d22 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
@@ -6,6 +6,9 @@
th_stopped_time: 1.0
collision_check_margin: 1.0
collision_check_distance_from_end: 1.0
+ th_moving_object_velocity: 1.0
+ th_distance_to_middle_of_the_road: 0.5
+ center_line_path_interval: 1.0
# shift pull out
enable_shift_pull_out: true
check_shift_path_lane_departure: false
@@ -18,7 +21,7 @@
maximum_curvature: 0.07
# geometric pull out
enable_geometric_pull_out: true
- divide_pull_out_path: false
+ divide_pull_out_path: true
geometric_pull_out_velocity: 1.0
arc_path_interval: 1.0
lane_departure_margin: 0.2
@@ -35,3 +38,102 @@
th_turn_signal_on_lateral_offset: 1.0
intersection_search_length: 30.0
length_ratio_for_turn_signal_deactivation_near_intersection: 0.5
+ # freespace planner
+ freespace_planner:
+ enable_freespace_planner: true
+ end_pose_search_start_distance: 20.0
+ end_pose_search_end_distance: 30.0
+ end_pose_search_interval: 2.0
+ freespace_planner_algorithm: "astar" # options: astar, rrtstar
+ velocity: 1.0
+ vehicle_shape_margin: 1.0
+ time_limit: 3000.0
+ minimum_turning_radius: 5.0
+ maximum_turning_radius: 5.0
+ turning_radius_size: 1
+ # search configs
+ search_configs:
+ theta_size: 144
+ angle_goal_range: 6.0
+ curve_weight: 1.2
+ reverse_weight: 1.0
+ lateral_goal_range: 0.5
+ longitudinal_goal_range: 2.0
+ # costmap configs
+ costmap_configs:
+ obstacle_threshold: 30
+ # -- A* search Configurations --
+ astar:
+ only_behind_solutions: false
+ use_back: false
+ distance_heuristic_weight: 1.0
+ # -- RRT* search Configurations --
+ rrtstar:
+ enable_update: true
+ use_informed_sampling: true
+ max_planning_time: 150.0
+ neighbor_radius: 8.0
+ margin: 1.0
+
+ stop_condition:
+ maximum_deceleration_for_stop: 1.0
+ maximum_jerk_for_stop: 1.0
+ path_safety_check:
+ # EgoPredictedPath
+ ego_predicted_path:
+ min_velocity: 0.0
+ acceleration: 1.0
+ max_velocity: 1.0
+ time_horizon_for_front_object: 10.0
+ time_horizon_for_rear_object: 10.0
+ time_resolution: 0.5
+ delay_until_departure: 1.0
+ # For target object filtering
+ target_filtering:
+ safety_check_time_horizon: 5.0
+ safety_check_time_resolution: 1.0
+ # detection range
+ object_check_forward_distance: 10.0
+ object_check_backward_distance: 100.0
+ ignore_object_velocity_threshold: 1.0
+ # ObjectTypesToCheck
+ object_types_to_check:
+ check_car: true
+ check_truck: true
+ check_bus: true
+ check_trailer: true
+ check_bicycle: true
+ check_motorcycle: true
+ check_pedestrian: true
+ check_unknown: false
+ # ObjectLaneConfiguration
+ object_lane_configuration:
+ check_current_lane: true
+ check_right_side_lane: true
+ check_left_side_lane: true
+ check_shoulder_lane: true
+ check_other_lane: false
+ include_opposite_lane: false
+ invert_opposite_lane: false
+ check_all_predicted_path: true
+ use_all_predicted_path: true
+ use_predicted_path_outside_lanelet: false
+
+ # For safety check
+ safety_check_params:
+ # safety check configuration
+ enable_safety_check: false # Don't set to true if auto_mode is enabled
+ # collision check parameters
+ check_all_predicted_path: true
+ publish_debug_marker: false
+ rss_params:
+ 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
+ # hysteresis factor to expand/shrink polygon
+ hysteresis_factor_expand_rate: 1.0
+ # temporary
+ backward_path_length: 30.0
+ forward_path_length: 100.0
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml
index 8a57bfeabd..0950ece4ae 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml
@@ -8,4 +8,4 @@
max_future_movement_time: 10.0 # [second]
threshold_yaw_diff: 0.523 # [rad]
adjacent_extend_width: 1.5 # [m]
- enable_rtc: true # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
+ enable_rtc: false # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
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 4b0a1ffc43..d99c70c5f6 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
@@ -5,7 +5,7 @@
show_processing_time: false # [-] whether to show processing time
# param for input data
traffic_light_state_timeout: 3.0 # [s] timeout threshold for traffic light signal
- enable_rtc: true # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
+ enable_rtc: false # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
# param for stop position
stop_position:
@@ -42,13 +42,21 @@
ego_pass_later_margin_x: [0.0] # [[s]] time to vehicle margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition)
ego_pass_later_margin_y: [10.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition)
ego_pass_later_additional_margin: 0.5 # [s] additional time margin for object pass first situation to suppress chattering
- max_offset_to_crosswalk_for_yield: 0.0 # [m] maximum offset from ego's front to crosswalk for yield. Positive value means in front of the crosswalk.
+
+ no_stop_decision:
+ max_offset_to_crosswalk_for_yield: 0.0 # [m] maximum offset from ego's front to crosswalk for yield. Positive value means in front of the crosswalk.
+ min_acc: -1.0 # min acceleration [m/ss]
+ min_jerk: -1.0 # min jerk [m/sss]
+ max_jerk: 1.0 # max jerk [m/sss]
+
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 crosswalk where there is a traffic signal
disable_yield_for_new_stopped_object: false # for the crosswalk where there is a traffic signal
- timeout_no_intention_to_walk: 3.0 # [s] if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first.
+ # 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] the amount of time which ego should be stopping to query whether it yields or not
# param for target object filtering
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml
index 55b627cce7..ddd8b934d2 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml
@@ -8,4 +8,4 @@
state_clear_time: 2.0
hold_stop_margin_distance: 0.0
distance_to_judge_over_stop_line: 0.5
- enable_rtc: true # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
+ enable_rtc: false # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
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 927a6bfaaf..11bdedf0d1 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
@@ -13,25 +13,46 @@
path_interpolation_ds: 0.1 # [m]
consider_wrong_direction_vehicle: false
stuck_vehicle:
+ turn_direction:
+ left: true
+ right: true
+ straight: true
use_stuck_stopline: true # stopline generated before the first conflicting area
- stuck_vehicle_detect_dist: 3.0 # this should be the length between cars when they are stopped. The actual stuck vehicle detection length will be this value + vehicle_length.
- stuck_vehicle_ignore_dist: 10.0 # obstacle stop max distance(5.0m) + stuck vehicle size / 2 (0.0m-)
+ stuck_vehicle_detect_dist: 5.0 # this should be the length between cars when they are stopped. The actual stuck vehicle detection length will be this value + vehicle_length.
stuck_vehicle_vel_thr: 0.833 # 0.833m/s = 3.0km/h
# enable_front_car_decel_prediction: false # By default this feature is disabled
# assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of front car when front car as well as ego are turning
timeout_private_area: 3.0 # [s] cancel stuck vehicle stop in private area
+ enable_private_area_stuck_disregard: false #In the intersections which labeled as "private area", the obstacle vehicles judged as "stuck" are neglected if this param is set as true.
+ yield_stuck:
+ turn_direction:
+ left: true
+ right: false
+ straight: false
+ distance_thr: 1.0 # [m]
collision_detection:
- state_transit_margin_time: 1.0
+ state_transit_margin_time: 0.0
min_predicted_path_confidence: 0.05
minimum_ego_predicted_velocity: 1.388 # [m/s]
- normal:
- collision_start_margin_time: 4.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object
- collision_end_margin_time: 6.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object
- relaxed:
+ fully_prioritized:
collision_start_margin_time: 2.0
collision_end_margin_time: 0.0
+ partially_prioritized:
+ collision_start_margin_time: 4.0
+ collision_end_margin_time: 6.0
+ not_prioritized:
+ collision_start_margin_time: 4.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object
+ collision_end_margin_time: 6.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object
keep_detection_vel_thr: 0.833 # == 3.0km/h. keep detection if ego is ego.vel < keep_detection_vel_thr
+ use_upstream_velocity: true # flag to use the planned velocity profile from the upstream module
+ minimum_upstream_velocity: 0.01 # [m/s] minimum velocity to avoid null division for the stop line from the upstream velocity
+ yield_on_green_traffic_light:
+ distance_to_assigned_lanelet_start: 10.0
+ duration: 3.0
+ object_dist_to_stopline: 10.0 # [m]
+ ignore_on_amber_traffic_light:
+ object_expected_deceleration: 2.0 # [m/ss]
occlusion:
enable: false
@@ -48,10 +69,19 @@
denoise_kernel: 1.0 # [m]
possible_object_bbox: [1.5, 2.5] # [m x m]
ignore_parked_vehicle_speed_threshold: 0.8333 # == 3.0km/h
+ stop_release_margin_time: 1.5 # [s]
+ temporal_stop_before_attention_area: false
+ absence_traffic_light:
+ creep_velocity: 1.388 # [m/s]
+ maximum_peeking_distance: 6.0 # [m]
+ attention_lane_crop_curvature_threshold: 0.25
+ attention_lane_curvature_calculation_ds: 0.5
enable_rtc:
- intersection: 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
- intersection_to_occlusion: true
+ intersection: 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
+ intersection_to_occlusion: false
merge_from_private:
+ stop_line_margin: 3.0
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/no_stopping_area.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml
index f550188d4f..c84848f8cc 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml
@@ -8,4 +8,4 @@
stop_line_margin: 1.0 # [m] margin to auto-gen stop line at no stopping area
detection_area_length: 200.0 # [m] used to create detection area polygon
stuck_vehicle_front_margin: 6.0 # [m] obstacle stop max distance(5.0m)
- 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
+ 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
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml
index dd4c1c6102..c74c5b3d87 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml
@@ -24,8 +24,7 @@
action: # action to insert in the path if an object causes a conflict at an overlap
skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed
- strict: true # if true, when a decision is taken to avoid entering a lane, the stop point will make sure no lane at all is entered by ego
- # if false, ego stops just before entering a lane but may then be overlapping another lane.
+ precision: 0.1 # [m] precision when inserting a stop pose in the path
distance_buffer: 1.5 # [m] buffer distance to try to keep between the ego footprint and lane
slowdown:
distance_threshold: 30.0 # [m] insert a slowdown when closer than this distance from an overlap
@@ -34,6 +33,7 @@
distance_threshold: 15.0 # [m] insert a stop when closer than this distance from an overlap
ego:
+ min_assumed_velocity: 2.0 # [m/s] minimum velocity used to calculate the enter and exit times of ego
extra_front_offset: 0.0 # [m] extra front distance
extra_rear_offset: 0.0 # [m] extra rear distance
extra_right_offset: 0.0 # [m] extra right distance
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 e8e0357daa..a837ae1b46 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
@@ -5,4 +5,4 @@
tl_state_timeout: 1.0
yellow_lamp_period: 2.75
enable_pass_judge: true
- 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
+ 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
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_replayer/rtc_replayer.param.yaml
similarity index 100%
rename from autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml
rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_replayer/rtc_replayer.param.yaml
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 f681398717..bb64006656 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
@@ -9,6 +9,7 @@
debug:
# flag to publish
enable_pub_debug_marker: true # publish debug marker
+ enable_pub_extra_debug_marker: false # publish extra debug marker
# flag to show
enable_debug_info: false
@@ -77,7 +78,7 @@
# avoidance
avoidance:
- max_bound_fixing_time: 3.0 # [s]
+ max_bound_fixing_time: 1.0 # [s]
max_longitudinal_margin_for_bound_violation: 1.0 # [m]
max_avoidance_cost: 0.5 # [m]
avoidance_cost_margin: 0.0 # [m]
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 b525d2914a..ddea1a9b56 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
@@ -14,10 +14,17 @@
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]
+ 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]
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]
+ stop_on_curve:
+ enable_approaching: false
+ additional_safe_distance_margin: 3.0 # [m]
+ min_safe_distance_margin: 3.0 # [m]
+ suppress_sudden_obstacle_stop: true
stop_obstacle_type:
unknown: true
@@ -99,6 +106,13 @@
successive_num_to_entry_slow_down_condition: 5
successive_num_to_exit_slow_down_condition: 5
+ # consider the current ego pose (it is not the nearest pose on the reference trajectory)
+ # Both the lateral error and the yaw error are assumed to decrease to zero by the time duration "time_to_convergence"
+ # The both errors decrease with constant rates against the time.
+ consider_current_pose:
+ enable_to_consider_current_pose: true
+ time_to_convergence: 1.5 #[s]
+
cruise:
pid_based_planner:
use_velocity_limit_based_planner: true
@@ -165,10 +179,13 @@
slow_down:
# parameters to calculate slow down velocity by linear interpolation
- min_lat_margin: 0.2
- max_lat_margin: 1.0
- min_ego_velocity: 2.0
- max_ego_velocity: 8.0
+ labels:
+ - "default"
+ default:
+ min_lat_margin: 0.2
+ max_lat_margin: 1.0
+ min_ego_velocity: 2.0
+ max_ego_velocity: 8.0
time_margin_on_target_velocity: 1.5 # [s]
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 6aa4e71774..5ec10572ff 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
@@ -1,11 +1,56 @@
/**:
ros__parameters:
-
# obstacle check
- use_pointcloud: true # use pointcloud as obstacle check
- use_dynamic_object: true # use dynamic object as obstacle check
- surround_check_distance: 0.5 # if objects exist in this distance, transit to "exist-surrounding-obstacle" status [m]
- surround_check_recover_distance: 0.8 # if no object exists in this distance, transit to "non-surrounding-obstacle" status [m]
+ # surround_check_*_distance: if objects exist in this distance, transit to "exist-surrounding-obstacle" status [m]
+ # surround_check_hysteresis_distance: if no object exists in this hysteresis distance added to the above distance, transit to "non-surrounding-obstacle" status [m]
+ pointcloud:
+ enable_check: false
+ surround_check_front_distance: 0.5
+ surround_check_side_distance: 0.5
+ surround_check_back_distance: 0.5
+ unknown:
+ enable_check: true
+ surround_check_front_distance: 0.5
+ surround_check_side_distance: 0.5
+ surround_check_back_distance: 0.5
+ car:
+ enable_check: true
+ surround_check_front_distance: 0.5
+ surround_check_side_distance: 0.0
+ surround_check_back_distance: 0.5
+ truck:
+ enable_check: true
+ surround_check_front_distance: 0.5
+ surround_check_side_distance: 0.0
+ surround_check_back_distance: 0.5
+ bus:
+ enable_check: true
+ surround_check_front_distance: 0.5
+ surround_check_side_distance: 0.0
+ surround_check_back_distance: 0.5
+ trailer:
+ enable_check: true
+ surround_check_front_distance: 0.5
+ surround_check_side_distance: 0.0
+ surround_check_back_distance: 0.5
+ motorcycle:
+ enable_check: true
+ surround_check_front_distance: 0.5
+ surround_check_side_distance: 0.0
+ surround_check_back_distance: 0.5
+ bicycle:
+ enable_check: true
+ surround_check_front_distance: 0.5
+ surround_check_side_distance: 0.5
+ surround_check_back_distance: 0.5
+ pedestrian:
+ enable_check: true
+ surround_check_front_distance: 0.5
+ surround_check_side_distance: 0.5
+ surround_check_back_distance: 0.5
+
+ surround_check_hysteresis_distance: 0.3
+
state_clear_time: 2.0
# ego stop state
@@ -13,3 +58,4 @@
# debug
publish_debug_footprints: true # publish vehicle footprint & footprints with surround_check_distance and surround_check_recover_distance offsets
+ debug_footprint_label: "car"
diff --git a/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml
index d6152c4f56..ffd99df533 100644
--- a/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml
@@ -37,3 +37,11 @@
only_behind_solutions: false
use_back: true
distance_heuristic_weight: 1.0
+
+ # -- RRT* search Configurations --
+ rrtstar:
+ enable_update: true
+ use_informed_sampling: true
+ max_planning_time: 150.0
+ neighbor_radius: 8.0
+ margin: 0.1
diff --git a/autoware_launch/config/system/duplicated_node_checker/duplicated_node_checker.param.yaml b/autoware_launch/config/system/duplicated_node_checker/duplicated_node_checker.param.yaml
new file mode 100644
index 0000000000..5b8c019de5
--- /dev/null
+++ b/autoware_launch/config/system/duplicated_node_checker/duplicated_node_checker.param.yaml
@@ -0,0 +1,3 @@
+/**:
+ ros__parameters:
+ update_rate: 10.0
diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml
new file mode 100644
index 0000000000..2f98f9d0e2
--- /dev/null
+++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml
@@ -0,0 +1,52 @@
+# Description:
+# name: diag name
+# sf_at: diag level where it becomes Safe Fault
+# lf_at: diag level where it becomes Latent Fault
+# spf_at: diag level where it becomes Single Point Fault
+# auto_recovery: Determines whether the system will automatically recover when it recovers from an error.
+#
+# Note:
+# empty-value for sf_at, lf_at and spf_at is "none"
+# default values are:
+# sf_at: "none"
+# lf_at: "warn"
+# spf_at: "error"
+# auto_recovery: "true"
+---
+/**:
+ ros__parameters:
+ required_modules:
+ autonomous_driving:
+ /autoware/control/autonomous_driving/node_alive_monitoring: default
+ /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default
+ /autoware/control/control_command_gate/node_alive_monitoring: default
+
+ /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: { sf_at: "warn", lf_at: "none", spf_at: "none" }
+
+ /autoware/map/node_alive_monitoring: default
+
+ /autoware/perception/node_alive_monitoring: default
+
+ /autoware/planning/node_alive_monitoring: default
+ /autoware/planning/performance_monitoring/trajectory_validation: default
+
+ # /autoware/sensing/node_alive_monitoring: default
+
+ /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: "none", spf_at: "none" }
+
+ /autoware/vehicle/node_alive_monitoring: default
+
+ external_control:
+ /autoware/control/control_command_gate/node_alive_monitoring: default
+ /autoware/control/external_control/external_command_selector/node_alive_monitoring: default
+
+ /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/vehicle/node_alive_monitoring: default
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 71dc2ac600..b8da5f4e7c 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
@@ -37,7 +37,8 @@
/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: "none", spf_at: "none" }
+ /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "error", spf_at: "none" }
+ /autoware/system/duplicated_node_checker: default
/autoware/vehicle/node_alive_monitoring: default
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 9708456df4..3fd6264376 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
@@ -19,6 +19,7 @@
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/trajectory_deviation: default
/autoware/control/control_command_gate/node_alive_monitoring: default
/autoware/localization/node_alive_monitoring: default
@@ -38,6 +39,7 @@
/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/duplicated_node_checker: default
/autoware/vehicle/node_alive_monitoring: default
diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml
index f702747ec9..5d98c9388f 100644
--- a/autoware_launch/launch/autoware.launch.xml
+++ b/autoware_launch/launch/autoware.launch.xml
@@ -6,6 +6,7 @@
+
@@ -32,9 +33,11 @@
+
+
@@ -88,7 +91,9 @@
-
+
+
+
@@ -108,6 +113,14 @@
-
+
diff --git a/autoware_launch/launch/components/tier4_control_component.launch.xml b/autoware_launch/launch/components/tier4_control_component.launch.xml
index 7b3169eacd..d15e050d7a 100644
--- a/autoware_launch/launch/components/tier4_control_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_control_component.launch.xml
@@ -5,6 +5,7 @@
+
@@ -35,11 +36,14 @@
+
+
+
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index 0dbbee6065..e3df873492 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -2,6 +2,13 @@
+
+
+
@@ -11,18 +18,16 @@
+
+
+
-
-
+
+
+
+
+
+
+
+
+
diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml
index ad55c76d82..a1cb2b79f5 100644
--- a/autoware_launch/launch/components/tier4_planning_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml
@@ -25,9 +25,6 @@
-
-
-
diff --git a/autoware_launch/launch/components/tier4_simulator_component.launch.xml b/autoware_launch/launch/components/tier4_simulator_component.launch.xml
index bd191f7a56..02f9a8243c 100644
--- a/autoware_launch/launch/components/tier4_simulator_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_simulator_component.launch.xml
@@ -43,5 +43,27 @@
+
+
+
+
+
+
+
diff --git a/autoware_launch/launch/components/tier4_system_component.launch.xml b/autoware_launch/launch/components/tier4_system_component.launch.xml
index 3cfc6d8541..a90fdb89a5 100644
--- a/autoware_launch/launch/components/tier4_system_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_system_component.launch.xml
@@ -1,5 +1,7 @@
+
+
@@ -8,9 +10,10 @@
+
-
+
diff --git a/autoware_launch/launch/e2e_simulator.launch.xml b/autoware_launch/launch/e2e_simulator.launch.xml
index a089da6397..fe8d1de1d8 100644
--- a/autoware_launch/launch/e2e_simulator.launch.xml
+++ b/autoware_launch/launch/e2e_simulator.launch.xml
@@ -4,6 +4,7 @@
+
@@ -18,12 +19,19 @@
+
+
+
@@ -34,6 +42,7 @@
+
@@ -52,10 +61,12 @@
+
+
diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml
index 6621c15ea3..7eb13135d3 100644
--- a/autoware_launch/launch/logging_simulator.launch.xml
+++ b/autoware_launch/launch/logging_simulator.launch.xml
@@ -5,6 +5,7 @@
+
diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml
index 941399db7e..fdc86ebba7 100644
--- a/autoware_launch/launch/planning_simulator.launch.xml
+++ b/autoware_launch/launch/planning_simulator.launch.xml
@@ -4,6 +4,7 @@
+
@@ -12,9 +13,6 @@
-
-
-
@@ -22,6 +20,11 @@
+
+
+
+
+
@@ -35,6 +38,7 @@
+
@@ -53,6 +57,7 @@
+
diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz
index 0dad17aaf9..00e924da39 100644
--- a/autoware_launch/rviz/autoware.rviz
+++ b/autoware_launch/rviz/autoware.rviz
@@ -16,8 +16,6 @@ Panels:
Expanded: ~
Name: Views
Splitter Ratio: 0.5
- - Class: tier4_localization_rviz_plugin/InitialPoseButtonPanel
- Name: InitialPoseButtonPanel
- Class: AutowareDateTimePanel
Name: AutowareDateTimePanel
- Class: rviz_plugins::AutowareStatePanel
@@ -86,6 +84,15 @@ Visualization Manager:
Value: /vehicle/status/velocity_status
Value: true
Value height offset: 0
+ - Class: rviz_plugins/AccelerationMeter
+ Enabled: false
+ Name: AccelerationMeter
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /localization/acceleration
- Alpha: 0.999
Class: rviz_plugins/VelocityHistory
Color Border Vel Max: 3
@@ -312,6 +319,22 @@ Visualization Manager:
Value: true
Enabled: true
Name: Vehicle
+ - Class: rviz_plugins/MrmSummaryOverlayDisplay
+ Enabled: false
+ Font Size: 10
+ Left: 512
+ Max Letter Num: 100
+ Name: MRM Summary
+ Text Color: 25; 255; 240
+ Top: 64
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /system/emergency/hazard_status
+ Value: false
+ Value height offset: 0
Enabled: true
Name: System
- Class: rviz_common/Group
@@ -2409,6 +2432,136 @@ Visualization Manager:
Value: false
Enabled: true
Name: Control
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_common/Group
+ Displays: ~
+ Enabled: true
+ Name: Map
+ - Class: rviz_common/Group
+ Displays: ~
+ Enabled: true
+ Name: Sensing
+ - Class: rviz_common/Group
+ Enabled: true
+ Name: Localization
+ Displays:
+ - Alpha: 0.9990000128746033
+ Autocompute Intensity Bounds: true
+ Autocompute Value Bounds:
+ Max Value: 10
+ Min Value: -10
+ Value: true
+ Axis: Z
+ Channel Name: intensity
+ Class: rviz_default_plugins/PointCloud2
+ Color: 85; 255; 0
+ Color Transformer: FlatColor
+ Decay Time: 0
+ Enabled: true
+ Invert Rainbow: false
+ Max Color: 85; 255; 127
+ Max Intensity: 0
+ Min Color: 0; 0; 0
+ Min Intensity: 0
+ Name: NDT pointclouds
+ Position Transformer: XYZ
+ Selectable: false
+ Size (Pixels): 10
+ Size (m): 0.5
+ Style: Squares
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /localization/pose_estimator/points_aligned
+ Use Fixed Frame: true
+ Use rainbow: true
+ Value: true
+ - Alpha: 1
+ Autocompute Intensity Bounds: true
+ Autocompute Value Bounds:
+ Max Value: 10
+ Min Value: -10
+ Value: true
+ Axis: Z
+ Channel Name: intensity
+ Class: rviz_default_plugins/PointCloud2
+ Color: 255; 255; 255
+ Color Transformer: ""
+ Decay Time: 0
+ Enabled: true
+ Invert Rainbow: false
+ Max Color: 255; 255; 255
+ Max Intensity: 4096
+ Min Color: 0; 0; 0
+ Min Intensity: 0
+ Name: NDTLoadedPCDMap
+ Position Transformer: ""
+ Selectable: true
+ Size (Pixels): 3
+ Size (m): 0.1
+ Style: Flat Squares
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /localization/pose_estimator/debug/loaded_pointcloud_map
+ Use Fixed Frame: true
+ Use rainbow: true
+ Value: true
+ - Buffer Size: 200
+ Class: rviz_plugins::PoseHistory
+ Enabled: true
+ Line:
+ Alpha: 0.9990000128746033
+ Color: 170; 255; 127
+ Value: true
+ Width: 0.10000000149011612
+ Name: NDTPoseHistory
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /localization/pose_estimator/pose
+ Value: true
+ - Buffer Size: 1000
+ Class: rviz_plugins::PoseHistory
+ Enabled: true
+ Line:
+ Alpha: 0.9990000128746033
+ Color: 0; 255; 255
+ Value: true
+ Width: 0.10000000149011612
+ Name: EKFPoseHistory
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ Filter size: 10
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /localization/pose_twist_fusion_filter/pose
+ Value: true
+ - Class: rviz_common/Group
+ Displays: ~
+ Enabled: true
+ Name: Perception
+ - Class: rviz_common/Group
+ Displays: ~
+ Enabled: true
+ Name: Planning
+ - Class: rviz_common/Group
+ Displays: ~
+ Enabled: true
+ Name: Control
+ Enabled: false
+ Name: Debug
Enabled: true
Global Options:
Background Color: 10; 10; 10