diff --git a/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
index 2fdb829aed..63c73e9fb6 100644
--- a/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
+++ b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
@@ -68,7 +68,7 @@
min_jerk: -2.0
# pitch
- use_trajectory_for_pitch_calculation: false
+ use_trajectory_for_pitch_calculation: true
lpf_pitch_gain: 0.95
max_pitch_rad: 0.1
min_pitch_rad: -0.1
diff --git a/autoware_launch/config/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 1758330718..2fd2ee8542 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
@@ -8,7 +8,7 @@
margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m]
# curve parameters
- max_lateral_accel: 1.0 # max lateral acceleration limit [m/ss]
+ max_lateral_accel: 0.6 # max lateral acceleration limit [m/ss]
min_curve_velocity: 2.74 # min velocity at lateral acceleration limit and steering angle rate limit [m/s]
decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit
decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/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 122b8bdcaf..e6fab6e5aa 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
@@ -10,7 +10,7 @@
enabled: true
ego:
extra_footprint_offset:
- front: 1.0 # [m] extra length to add to the front of the ego footprint
+ front: 1.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
@@ -26,12 +26,12 @@
# '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)
+ max_path_arc_length: 80.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
avoid_linestring:
types: # linestring types in the lanelet maps that will not be crossed when expanding the drivable area
- road_border
- distance: 0.0 # [m] distance to keep between the drivable area and the linestrings to avoid
+ distance: 0.3 # [m] distance to keep between the drivable area and the linestrings to avoid
compensate:
enable: false # 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/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 cd2bc6168d..6cd6b1f06d 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,7 +2,7 @@
ros__parameters:
goal_planner:
# general params
- minimum_request_length: 100.0
+ minimum_request_length: 10.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.
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 4e77e0591f..696113d6bf 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
@@ -54,5 +54,5 @@
intersection_to_occlusion: true
merge_from_private:
- stop_line_margin: 3.0
+ stop_line_margin: 0.5
stop_duration_sec: 1.0
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/walkway.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/walkway.param.yaml
index f102af1b2e..2bdfacd868 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/walkway.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/walkway.param.yaml
@@ -1,5 +1,5 @@
/**:
ros__parameters:
walkway:
- stop_duration: 1.0 # [s] stop time at stop position
- stop_distance_from_crosswalk: 0.5 # [m] make stop line away from crosswalk when no explicit stop line exists
+ stop_duration: 0.1 # [s] stop time at stop position
+ stop_distance_from_crosswalk: 0.0 # [m] make stop line away from crosswalk when no explicit stop line exists
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml
index 9d761b15ee..c0e3e147dc 100644
--- 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_auto_mode_manager/rtc_auto_mode_manager.param.yaml
@@ -26,8 +26,8 @@
- "traffic_light"
- "lane_change_left"
- "lane_change_right"
- - "avoidance_left"
- - "avoidance_right"
+ # - "avoidance_left"
+ # - "avoidance_right"
- "avoidance_by_lane_change_left"
- "avoidance_by_lane_change_right"
- "goal_planner"
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml
index 0bf78ead05..0a44d8aabd 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml
@@ -45,13 +45,13 @@
common:
num_points: 100 # number of points for optimization [-]
- delta_arc_length: 1.0 # delta arc length for optimization [m]
+ delta_arc_length: 0.5 # delta arc length for optimization [m]
kinematics:
# If this parameter is commented out, the parameter is set as below by default.
# The logic could be `optimization_center_offset = vehicle_info.wheelbase * 0.8`
# The 0.8 scale is adopted as it performed the best.
- optimization_center_offset: 0.0 # optimization center offset from base link
+ optimization_center_offset: 2.0 # optimization center offset from base link
clearance: # clearance(distance) between vehicle and roads/objects when generating trajectory
# if collision_free_constraints.option.hard_constraint is true
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml
index b71c2d667c..a01df1447c 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml
@@ -13,7 +13,7 @@
min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss]
min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss]
safe_distance_margin : 6.0 # This is also used as a stop margin [m]
- terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m]
+ terminal_safe_distance_margin : 6.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m]
hold_stop_velocity_threshold: 0.01 # The maximum ego velocity to hold stopping [m/s]
hold_stop_distance_threshold: 0.3 # The ego keeps stopping if the distance to stop changes within the threshold [m]
diff --git a/autoware_launch/launch/e2e_simulator.launch.xml b/autoware_launch/launch/e2e_simulator.launch.xml
index a089da6397..b33e325f14 100644
--- a/autoware_launch/launch/e2e_simulator.launch.xml
+++ b/autoware_launch/launch/e2e_simulator.launch.xml
@@ -59,6 +59,8 @@
+
+