diff --git a/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml
index 4222082d40..9998b6aadf 100644
--- a/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml
+++ b/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml
@@ -74,3 +74,5 @@
update_steer_threshold: 0.035
average_num: 1000
steering_offset_limit: 0.02
+
+ debug_publish_predicted_trajectory: false # publish debug predicted trajectory in Frenet coordinate
diff --git a/autoware_launch/config/localization/ekf_localizer.param.yaml b/autoware_launch/config/localization/ekf_localizer.param.yaml
index 1c16624605..ebdf2828fc 100644
--- a/autoware_launch/config/localization/ekf_localizer.param.yaml
+++ b/autoware_launch/config/localization/ekf_localizer.param.yaml
@@ -4,6 +4,7 @@
enable_yaw_bias_estimation: true
predict_frequency: 50.0
tf_rate: 50.0
+ publish_tf: true
extend_state_step: 50
# for Pose measurement
@@ -22,6 +23,10 @@
proc_stddev_vx_c: 10.0
proc_stddev_wz_c: 5.0
+ #Simple1DFilter parameters
+ z_filter_proc_dev: 1.0
+ roll_filter_proc_dev: 0.01
+ pitch_filter_proc_dev: 0.01
# for diagnostics
pose_no_update_count_threshold_warn: 50
pose_no_update_count_threshold_error: 100
diff --git a/autoware_launch/config/perception/object_recognition/detection/detection_by_tracker/detection_by_tracker.param.yaml b/autoware_launch/config/perception/object_recognition/detection/detection_by_tracker/detection_by_tracker.param.yaml
index 6957040506..fac8687c5e 100644
--- a/autoware_launch/config/perception/object_recognition/detection/detection_by_tracker/detection_by_tracker.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/detection_by_tracker/detection_by_tracker.param.yaml
@@ -1,11 +1,10 @@
/**:
ros__parameters:
- tracker_ignore_label:
- UNKNOWN : true
- CAR : false
- TRUCK : false
- BUS : false
- TRAILER : false
- MOTORCYCLE : false
- BICYCLE : false
- PEDESTRIAN : false
+ tracker_ignore_label.UNKNOWN : true
+ tracker_ignore_label.CAR : false
+ tracker_ignore_label.TRUCK : false
+ tracker_ignore_label.BUS : false
+ tracker_ignore_label.TRAILER : false
+ tracker_ignore_label.MOTORCYCLE : false
+ tracker_ignore_label.BICYCLE : false
+ tracker_ignore_label.PEDESTRIAN : false
diff --git a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_cluster_fusion.param.yaml b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_cluster_fusion.param.yaml
new file mode 100644
index 0000000000..016a133227
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_cluster_fusion.param.yaml
@@ -0,0 +1,12 @@
+/**:
+ ros__parameters:
+ fusion_distance: 100.0
+ trust_object_distance: 100.0
+ trust_object_iou_mode: "iou"
+ non_trust_object_iou_mode: "iou_x"
+ use_cluster_semantic_type: false
+ only_allow_inside_cluster: true
+ roi_scale_factor: 1.1
+ iou_threshold: 0.65
+ unknown_iou_threshold: 0.1
+ remove_unknown: false
diff --git a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_detected_object_fusion.param.yaml b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_detected_object_fusion.param.yaml
new file mode 100755
index 0000000000..bd49dc6574
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_detected_object_fusion.param.yaml
@@ -0,0 +1,19 @@
+/**:
+ ros__parameters:
+ # UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ passthrough_lower_bound_probability_thresholds: [0.35, 0.35, 0.35, 0.35, 0.35, 0.35, 0.35, 0.50]
+ trust_distances: [50.0, 100.0, 100.0, 100.0, 100.0, 50.0, 50.0, 50.0]
+ min_iou_threshold: 0.5
+ use_roi_probability: false
+ roi_probability_threshold: 0.5
+
+ can_assign_matrix:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN <-roi_msg
+ [1, 0, 0, 0, 0, 0, 0, 0, # UNKNOWN <-detected_objects
+ 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
diff --git a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_pointcloud_fusion.param.yaml b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_pointcloud_fusion.param.yaml
new file mode 100644
index 0000000000..5b86b8e81d
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_pointcloud_fusion.param.yaml
@@ -0,0 +1,5 @@
+/**:
+ ros__parameters:
+ fuse_unknown_only: true
+ min_cluster_size: 2
+ cluster_2d_tolerance: 0.5
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 fe4d2a51ec..fdd64174de 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
@@ -16,6 +16,9 @@
check_lateral_acceleration_constraints: false # whether to check if the predicted path complies with lateral acceleration constraints
max_lateral_accel: 2.0 # [m/ss] max acceptable lateral acceleration for predicted vehicle paths
min_acceleration_before_curve: -2.0 # [m/ss] min acceleration a vehicle might take to decelerate before a curve
+ use_vehicle_acceleration: false # whether to consider current vehicle acceleration when predicting paths or not
+ speed_limit_multiplier: 1.5 # When using vehicle acceleration. Set vehicle's maximum predicted speed as the legal speed limit in that lanelet times this value
+ acceleration_exponential_half_life: 2.5 # [s] When using vehicle acceleration. The decaying acceleration model considers that the current vehicle acceleration will be halved after this many seconds
# parameter for shoulder lane prediction
prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8
diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml
index 3df13a108d..3512d722ec 100644
--- a/autoware_launch/config/planning/preset/default_preset.yaml
+++ b/autoware_launch/config/planning/preset/default_preset.yaml
@@ -112,7 +112,7 @@ launch:
- arg:
name: launch_surround_obstacle_checker
- default: "true"
+ default: "false"
# parking modules
- arg:
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 0618185dcf..d540a73940 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
@@ -122,7 +122,8 @@
motorcycle: true # [-]
pedestrian: true # [-]
# detection range
- object_check_goal_distance: 20.0 # [m]
+ object_check_goal_distance: 20.0 # [m]
+ object_check_return_pose_distance: 20.0 # [m]
# filtering parking objects
threshold_distance_object_is_on_center: 1.0 # [m]
object_check_shiftable_ratio: 0.6 # [-]
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lc/avoidance_by_lc.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lane_change/avoidance_by_lane_change.param.yaml
similarity index 100%
rename from autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lc/avoidance_by_lc.param.yaml
rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lane_change/avoidance_by_lane_change.param.yaml
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml
index 06fe74e3b7..d03efa405f 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
@@ -38,6 +38,7 @@
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
+ detection_bound_offset: 15.0
# pull over
pull_over:
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml
index 0090a29926..9853e220bc 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
@@ -53,7 +53,7 @@
goal_planner:
enable_rtc: false
- enable_simultaneous_execution_as_approved_module: false
+ enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
keep_last: true
priority: 1
@@ -67,7 +67,7 @@
priority: 4
max_module_size: 1
- avoidance_by_lc:
+ avoidance_by_lane_change:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
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 592302ce5d..ddfc8fab52 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
@@ -13,7 +13,7 @@
center_line_path_interval: 1.0
# shift pull out
enable_shift_pull_out: true
- check_shift_path_lane_departure: false
+ check_shift_path_lane_departure: true
minimum_shift_pull_out_distance: 0.0
deceleration_interval: 15.0
lateral_jerk: 0.5
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 240963309e..72102ed908 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
@@ -16,7 +16,7 @@
# For the case where the crosswalk width is very wide
far_object_threshold: 10.0 # [m] If objects cross X meters behind the stop line, the stop position is determined according to the object position (stop_distance_from_object meters before the object).
# For the case where the stop position is determined according to the object position.
- stop_distance_from_object: 2.0 # [m] the vehicle decelerates to be able to stop in front of object with margin
+ stop_distance_from_object: 3.0 # [m] the vehicle decelerates to be able to stop in front of object with margin
# params for ego's slow down velocity. These params are not used for the case of "enable_rtc: false".
slow_down:
@@ -38,7 +38,7 @@
# params for the pass judge logic against the crosswalk users such as pedestrians or bicycles
pass_judge:
ego_pass_first_margin_x: [0.0] # [[s]] time to collision margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition)
- ego_pass_first_margin_y: [6.0] # [[s]] time to vehicle margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition)
+ ego_pass_first_margin_y: [3.0] # [[s]] time to vehicle margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition)
ego_pass_first_additional_margin: 0.5 # [s] additional time margin for ego pass first situation to suppress chattering
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)
@@ -50,19 +50,19 @@
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)
+ stop_object_velocity_threshold: 0.25 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.25 m/s = 0.9 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: true # for the crosswalks with traffic signal
disable_yield_for_new_stopped_object: true # for the crosswalks with traffic signal
# If the pedestrian does not move for X seconds after the ego has stopped in front the crosswalk, the module judge that the pedestrian has no intention to walk and allows the ego to proceed.
distance_map_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order
- timeout_map_for_no_intention_to_walk: [3.0, 0.0] # [s]
- timeout_ego_stop_for_yield: 3.0 # [s] If the ego maintains the stop for this amount of time, then the ego proceeds, assuming it has stopped long time enough.
+ timeout_map_for_no_intention_to_walk: [1.0, 0.0] # [s]
+ timeout_ego_stop_for_yield: 1.0 # [s] If the ego maintains the stop for this amount of time, then the ego proceeds, assuming it has stopped long time enough.
# param for target object filtering
object_filtering:
- crosswalk_attention_range: 1.0 # [m] the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk
+ crosswalk_attention_range: 2.0 # [m] the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk
vehicle_object_cross_angle_threshold: 0.5 # [rad] threshold judging object is crossing walkway as a pedestrian or passing over as a vehicle
target_object:
unknown: true # [-] whether to look and stop by UNKNOWN objects
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 4e9eb50f2a..238d40e7ad 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml
@@ -12,6 +12,7 @@
max_accel: -2.8
max_jerk: -5.0
delay_response_time: 0.5
+ enable_pass_judge_before_default_stopline: false
stuck_vehicle:
turn_direction:
@@ -36,7 +37,6 @@
consider_wrong_direction_vehicle: false
collision_detection_hold_time: 0.5
min_predicted_path_confidence: 0.05
- keep_detection_velocity_threshold: 0.833
velocity_profile:
use_upstream: true
minimum_upstream_velocity: 0.01
@@ -67,7 +67,7 @@
occupied_min: 58
denoise_kernel: 1.0
attention_lane_crop_curvature_threshold: 0.25
- attention_lane_curvature_calculation_ds: 0.5
+ attention_lane_curvature_calculation_ds: 0.6
creep_during_peeking:
enable: false
creep_velocity: 0.8333
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml
index 86bcf34382..196f7c6296 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml
@@ -3,7 +3,7 @@
run_out:
detection_method: "Object" # [-] candidate: Object, ObjectWithoutPath, Points
use_partition_lanelet: true # [-] whether to use partition lanelet map data
- suppress_on_crosswalk: true # [-] whether to suppress on crosswalk lanelet:
+ suppress_on_crosswalk: true # [-] whether to suppress on crosswalk lanelet
specify_decel_jerk: true # [-] whether to specify jerk when ego decelerates
stop_margin: 2.5 # [m] the vehicle decelerates to be able to stop with this margin
passing_margin: 1.1 # [m] the vehicle begins to accelerate if the vehicle's front in predicted position is ahead of the obstacle + this margin
@@ -12,15 +12,7 @@
detection_span: 1.0 # [m] calculate collision with this span to reduce calculation time
min_vel_ego_kmph: 3.6 # [km/h] min velocity to calculate time to collision
- detection_area:
- margin_behind: 0.5 # [m] ahead margin for detection area length
- margin_ahead: 1.0 # [m] behind margin for detection area length
-
- # This area uses points not filtered by vector map to ensure safety
- mandatory_area:
- decel_jerk: -1.2 # [m/s^3] deceleration jerk for obstacles in this area
-
- # parameter to create abstracted dynamic obstacles
+ # Parameter to create abstracted dynamic obstacles
dynamic_obstacle:
use_mandatory_area: false # [-] whether to use mandatory detection area
assume_fixed_velocity:
@@ -34,26 +26,42 @@
time_step: 0.5 # [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path
points_interval: 0.1 # [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method
- # approach if ego has stopped in the front of the obstacle for a certain amount of time
- approaching:
- enable: false
- margin: 0.0 # [m] distance on how close ego approaches the obstacle
- limit_vel_kmph: 3.0 # [km/h] limit velocity for approaching after stopping
-
- # parameters for the change of state. used only when approaching is enabled
- state:
- stop_thresh: 0.01 # [m/s] threshold to decide if ego is stopping
- stop_time_thresh: 3.0 # [sec] threshold for stopping time to transit to approaching state
- disable_approach_dist: 3.0 # [m] end the approaching state if distance to the obstacle is longer than this value
- keep_approach_duration: 1.0 # [sec] keep approach state for this duration to avoid chattering of state transition
-
- # parameter to avoid sudden stopping
+ # Parameter to prevent sudden stopping.
+ # If the deceleration jerk and acceleration exceed this value upon inserting a stop point,
+ # the deceleration will be moderated to stay under this value.
slow_down_limit:
enable: false
max_jerk: -0.7 # [m/s^3] minimum jerk deceleration for safe brake.
max_acc : -2.0 # [m/s^2] minimum accel deceleration for safe brake.
- # prevent abrupt stops caused by false positives in perception
+ # Parameter to prevent abrupt stops caused by false positives in perception
ignore_momentary_detection:
enable: true
time_threshold: 0.15 # [sec] ignores detections that persist for less than this duration
+
+ # Typically used when the "detection_method" is set to ObjectWithoutPath or Points
+ # Approach if the ego has stopped in front of the obstacle for a certain period
+ # This avoids the issue of the ego continuously stopping in front of the obstacle
+ approaching:
+ enable: false
+ margin: 0.0 # [m] distance on how close ego approaches the obstacle
+ limit_vel_kmph: 3.0 # [km/h] limit velocity for approaching after stopping
+ # Parameters for state change when "approaching" is enabled
+ state:
+ stop_thresh: 0.01 # [m/s] threshold to decide if ego is stopping
+ stop_time_thresh: 3.0 # [sec] threshold for stopping time to transit to approaching state
+ disable_approach_dist: 3.0 # [m] end the approaching state if distance to the obstacle is longer than this value
+ keep_approach_duration: 1.0 # [sec] keep approach state for this duration to avoid chattering of state transition
+
+ # Only used when "detection_method" is set to Points
+ # Filters points by the detection area polygon to reduce computational cost
+ # The detection area is calculated based on the current velocity and acceleration and deceleration jerk constraints
+ detection_area:
+ margin_behind: 0.5 # [m] ahead margin for detection area length
+ margin_ahead: 1.0 # [m] behind margin for detection area length
+
+ # Only used when "detection_method" is set to Points
+ # Points in this area are detected even if it is in the no obstacle segmentation area
+ # The mandatory area is calculated based on the current velocity and acceleration and "decel_jerk" constraints
+ mandatory_area:
+ decel_jerk: -1.2 # [m/s^3] deceleration jerk for obstacles in this area
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/walkway.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/walkway.param.yaml
index f21e3d12db..07f493edcd 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/walkway.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/walkway.param.yaml
@@ -1,5 +1,5 @@
/**:
ros__parameters:
walkway:
- stop_duration: 1.0 # [s] stop time at stop position
+ stop_duration: 0.1 # [s] stop time at stop position
stop_distance_from_crosswalk: 3.5 # [m] make stop line away from crosswalk when no explicit stop line exists
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml
index 9ab8f42bcf..db89a81e47 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
@@ -31,7 +31,7 @@
max_ego_moving_dist: 5.0 # threshold of ego's moving distance for replan [m]
# make max_goal_moving_dist long to keep start point fixed for pull over
max_goal_moving_dist: 15.0 # threshold of goal's moving distance for replan [m]
- max_delta_time_sec: 1.0 # threshold of delta time for replan [second]
+ max_delta_time_sec: 0.0 # threshold of delta time for replan [second]
# mpt param
mpt:
@@ -40,7 +40,7 @@
steer_limit_constraint: false
visualize_sampling_num: 1
enable_manual_warm_start: false
- enable_warm_start: true
+ enable_warm_start: false
enable_optimization_validation: false
common:
@@ -62,7 +62,7 @@
# weight parameter for optimization
weight:
# collision free
- soft_collision_free_weight: 1000.0 # soft weight for lateral error around the middle point
+ soft_collision_free_weight: 1.0 # soft weight for lateral error around the middle point
# tracking error
lat_error_weight: 1.0 # weight for lateral error
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml
index 90e897fda3..1ac32ba562 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
@@ -85,15 +85,15 @@
obstacle_traj_angle_threshold : 1.22 # [rad] = 70 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop
stop:
- max_lat_margin: 0.0 # lateral margin between obstacle and trajectory band with ego's width
+ max_lat_margin: 0.2 # lateral margin between obstacle and trajectory band with ego's width
crossing_obstacle:
collision_time_margin : 4.0 # time threshold of collision between obstacle adn ego for cruise or stop [s]
cruise:
max_lat_margin: 1.0 # lateral margin between obstacle and trajectory band with ego's width
outside_obstacle:
- obstacle_velocity_threshold : 3.0 # minimum velocity threshold of obstacles outside the trajectory to cruise or stop [m/s]
- ego_obstacle_overlap_time_threshold : 1.0 # time threshold to decide cut-in obstacle for cruise or stop [s]
+ obstacle_velocity_threshold : 3.5 # minimum velocity threshold of obstacles outside the trajectory to cruise or stop [m/s]
+ ego_obstacle_overlap_time_threshold : 2.0 # time threshold to decide cut-in obstacle for cruise or stop [s]
max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego
slow_down:
@@ -187,7 +187,7 @@
static:
min_lat_margin: 0.2
max_lat_margin: 1.0
- min_ego_velocity: 2.0
+ min_ego_velocity: 4.0
max_ego_velocity: 8.0
moving_object_speed_threshold: 0.5 # [m/s] how fast the object needs to move to be considered as "moving"
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_smoother/elastic_band_smoother.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_smoother/elastic_band_smoother.param.yaml
index c67d29c418..a9e71368e3 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_smoother/elastic_band_smoother.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_smoother/elastic_band_smoother.param.yaml
@@ -44,4 +44,4 @@
max_ego_moving_dist: 5.0 # threshold of ego's moving distance for replan [m]
# make max_goal_moving_dist long to keep start point fixed for pull over
max_goal_moving_dist: 15.0 # threshold of goal's moving distance for replan [m]
- max_delta_time_sec: 1.0 # threshold of delta time for replan [second]
+ max_delta_time_sec: 0.0 # threshold of delta time for replan [second]
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml
index 5ec10572ff..7f72420b3a 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml
@@ -9,7 +9,7 @@
surround_check_side_distance: 0.5
surround_check_back_distance: 0.5
unknown:
- enable_check: true
+ enable_check: false
surround_check_front_distance: 0.5
surround_check_side_distance: 0.5
surround_check_back_distance: 0.5
@@ -17,22 +17,22 @@
enable_check: true
surround_check_front_distance: 0.5
surround_check_side_distance: 0.0
- surround_check_back_distance: 0.5
+ surround_check_back_distance: 0.0
truck:
enable_check: true
surround_check_front_distance: 0.5
surround_check_side_distance: 0.0
- surround_check_back_distance: 0.5
+ surround_check_back_distance: 0.0
bus:
enable_check: true
surround_check_front_distance: 0.5
surround_check_side_distance: 0.0
- surround_check_back_distance: 0.5
+ surround_check_back_distance: 0.0
trailer:
enable_check: true
surround_check_front_distance: 0.5
surround_check_side_distance: 0.0
- surround_check_back_distance: 0.5
+ surround_check_back_distance: 0.0
motorcycle:
enable_check: true
surround_check_front_distance: 0.5
@@ -49,9 +49,9 @@
surround_check_side_distance: 0.5
surround_check_back_distance: 0.5
- surround_check_hysteresis_distance: 0.3
+ surround_check_hysteresis_distance: 0.1
- state_clear_time: 2.0
+ state_clear_time: 0.2
# ego stop state
stop_state_ego_speed: 0.1 #[m/s]
diff --git a/autoware_launch/config/vehicle/raw_vehicle_cmd_converter/raw_vehicle_cmd_converter.param.yaml b/autoware_launch/config/vehicle/raw_vehicle_cmd_converter/raw_vehicle_cmd_converter.param.yaml
new file mode 100644
index 0000000000..f6676bdbe7
--- /dev/null
+++ b/autoware_launch/config/vehicle/raw_vehicle_cmd_converter/raw_vehicle_cmd_converter.param.yaml
@@ -0,0 +1,25 @@
+/**:
+ ros__parameters:
+ convert_accel_cmd: true
+ convert_brake_cmd: true
+ convert_steer_cmd: false
+ use_steer_ff: true
+ use_steer_fb: true
+ is_debugging: false
+ max_throttle: 0.4
+ max_brake: 0.8
+ max_steer: 10.0
+ min_steer: -10.0
+ steer_pid:
+ kp: 150.0
+ ki: 15.0
+ kd: 0.0
+ max: 8.0
+ min: -8.0
+ max_p: 8.0
+ min_p: -8.0
+ max_i: 8.0
+ min_i: -8.0
+ max_d: 0.0
+ min_d: 0.0
+ invalid_integration_decay: 0.97
diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml
index 80822d0146..a2cd12b2c1 100644
--- a/autoware_launch/launch/autoware.launch.xml
+++ b/autoware_launch/launch/autoware.launch.xml
@@ -44,6 +44,8 @@
+
+
@@ -69,6 +71,7 @@
+
@@ -103,6 +106,7 @@
+
diff --git a/autoware_launch/launch/components/tier4_localization_component.launch.xml b/autoware_launch/launch/components/tier4_localization_component.launch.xml
index 88b326b2f7..7ec292a381 100644
--- a/autoware_launch/launch/components/tier4_localization_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_localization_component.launch.xml
@@ -4,15 +4,19 @@
+
-
-
+
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index 3a968f0f27..939792af84 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -13,7 +13,6 @@
-
@@ -48,6 +47,18 @@
name="object_recognition_detection_fusion_sync_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml"
/>
+
+
+
+
+
@@ -24,7 +26,7 @@
-
+
diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml
index 28a0f0e347..030299f5af 100644
--- a/autoware_launch/launch/planning_simulator.launch.xml
+++ b/autoware_launch/launch/planning_simulator.launch.xml
@@ -30,6 +30,8 @@
+
+
@@ -63,6 +65,8 @@
+
+
diff --git a/autoware_launch/launch/pointcloud_container.launch.py b/autoware_launch/launch/pointcloud_container.launch.py
index 87c46bce69..650e555e27 100644
--- a/autoware_launch/launch/pointcloud_container.launch.py
+++ b/autoware_launch/launch/pointcloud_container.launch.py
@@ -19,6 +19,7 @@
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
+from launch_ros.descriptions import ComposableNode
def generate_launch_description():
@@ -37,13 +38,20 @@ def add_launch_arg(name: str, default_value=None):
condition=IfCondition(LaunchConfiguration("use_multithread")),
)
+ glog_component = ComposableNode(
+ package="glog_component",
+ plugin="GlogComponent",
+ name="glog_component",
+ namespace="pointcloud_container",
+ )
+
pointcloud_container = ComposableNodeContainer(
name=LaunchConfiguration("container_name"),
namespace="/",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
- composable_node_descriptions=[],
- output="screen",
+ composable_node_descriptions=[glog_component],
+ output="both",
)
return LaunchDescription(
diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz
index a0ade56821..064f87d3ff 100644
--- a/autoware_launch/rviz/autoware.rviz
+++ b/autoware_launch/rviz/autoware.rviz
@@ -3649,6 +3649,22 @@ Visualization Manager:
Value: true
Enabled: true
Name: Objects Of Interest
+ - Class: rviz_plugins/StringStampedOverlayDisplay
+ Enabled: true
+ Font Size: 15
+ Left: 1024
+ Max Letter Num: 100
+ Name: StringStampedOverlayDisplay
+ Text Color: 25; 255; 240
+ Top: 128
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/internal_state
+ Value: true
+ Value height offset: 0
Enabled: true
Name: Planning
- Class: rviz_common/Group