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/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 273db320f1..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
@@ -50,15 +50,15 @@
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:
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_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/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/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml
index 80822d0146..64bdf47c72 100644
--- a/autoware_launch/launch/autoware.launch.xml
+++ b/autoware_launch/launch/autoware.launch.xml
@@ -44,6 +44,8 @@
+
+
@@ -103,6 +105,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 21373c78e4..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 @@
-
diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml
index 4711f4b7f0..4e65c30c02 100644
--- a/autoware_launch/launch/components/tier4_planning_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml
@@ -2,12 +2,14 @@
+
+
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 @@
+
+