diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml
index 5a3139e4c5..0ffeeeccf0 100644
--- a/autoware_launch/config/planning/preset/default_preset.yaml
+++ b/autoware_launch/config/planning/preset/default_preset.yaml
@@ -8,7 +8,7 @@ launch:
default: "true"
- arg:
name: launch_dynamic_obstacle_avoidance
- default: "false"
+ default: "true"
- arg:
name: launch_sampling_planner_module
default: "false" # Warning, experimental module, use only in simulations
@@ -120,7 +120,7 @@ launch:
- arg:
name: launch_surround_obstacle_checker
- default: "false"
+ default: "true"
# parking modules
- arg:
diff --git a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml
index 4edbbf2d35..5680a99713 100644
--- a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml
@@ -1,6 +1,6 @@
/**:
ros__parameters:
- max_vel: 4.17 # max velocity limit [m/s]
+ max_vel: 11.1 # max velocity limit [m/s]
# constraints param for normal driving
normal:
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 c9ac6aa1a6..069f336959 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
@@ -89,7 +89,7 @@
object_time_margin_to_collision_point: 4.0
occlusion:
- enable: false
+ enable: true
occlusion_attention_area_length: 70.0
free_space_max: 43
occupied_min: 58
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/autoware_path_optimizer/path_optimizer.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/autoware_path_optimizer/path_optimizer.param.yaml
index db89a81e47..17a044fb67 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/autoware_path_optimizer/path_optimizer.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/autoware_path_optimizer/path_optimizer.param.yaml
@@ -3,7 +3,7 @@
option:
enable_skip_optimization: false # skip elastic band and model predictive trajectory
enable_reset_prev_optimization: false # If true, optimization has no fix constraint to the previous result.
- enable_outside_drivable_area_stop: true # stop if the ego's trajectory footprint is outside the drivable area
+ enable_outside_drivable_area_stop: false # stop if the ego's trajectory footprint is outside the drivable area
use_footprint_polygon_for_outside_drivable_area_check: false # If false, only the footprint's corner points are considered.
debug:
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 4b9e96f6bc..2213cc39dc 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
@@ -12,7 +12,7 @@
idling_time: 2.0 # idling time to detect front vehicle starting deceleration [s]
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 : 4.0 # This is also used as a stop margin [m]
+ safe_distance_margin : 5.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]
@@ -99,8 +99,8 @@
stop_obstacle_hold_time_threshold : 1.0 # maximum time for holding closest stop obstacle
# hysteresis for cruise and stop
- obstacle_velocity_threshold_from_cruise_to_stop : 1.0 # stop planning is executed to the obstacle whose velocity is less than this value [m/s]
- obstacle_velocity_threshold_from_stop_to_cruise : 1.5 # stop planning is executed to the obstacle whose velocity is less than this value [m/s]
+ obstacle_velocity_threshold_from_cruise_to_stop : 3.0 # stop planning is executed to the obstacle whose velocity is less than this value [m/s]
+ obstacle_velocity_threshold_from_stop_to_cruise : 3.5 # stop planning is executed to the obstacle whose velocity is less than this value [m/s]
# if crossing vehicle is determined as target obstacles or not
crossing_obstacle:
@@ -126,7 +126,7 @@
ego_obstacle_overlap_time_threshold : 0.2 # time threshold to decide cut-in obstacle for cruise or stop [s]
max_prediction_time_for_collision_check : 10.0 # prediction time to check collision between obstacle and ego
max_lateral_time_margin: 5.0 # time threshold of lateral margin between obstacle and trajectory band with ego's width [s]
- num_of_predicted_paths: 3 # number of the highest confidence predicted path to check collision between obstacle and ego
+ num_of_predicted_paths: 1 # number of the highest confidence predicted path to check collision between obstacle and ego
yield:
enable_yield: true
lat_distance_threshold: 5.0 # lateral margin between obstacle in neighbor lanes and trajectory band with ego's width for yielding
diff --git a/autoware_launch/config/system/system_diagnostic_monitor/control.yaml b/autoware_launch/config/system/system_diagnostic_monitor/control.yaml
index 5551ed4575..6a04ed6714 100644
--- a/autoware_launch/config/system/system_diagnostic_monitor/control.yaml
+++ b/autoware_launch/config/system/system_diagnostic_monitor/control.yaml
@@ -9,6 +9,7 @@ units:
- { type: link, link: /autoware/control/performance_monitoring/lane_departure }
- { type: link, link: /autoware/control/performance_monitoring/trajectory_deviation }
- { type: link, link: /autoware/control/performance_monitoring/control_state }
+ - { type: link, link: /autoware/control/collision_detector }
- path: /autoware/control/local
type: and
@@ -66,3 +67,8 @@ units:
type: diag
node: external_cmd_converter
name: remote_control_topic_status
+
+ - path: /autoware/control/collision_detector
+ type: diag
+ node: collision_detector
+ name: collision_detect
diff --git a/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml b/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml
index 1c7b520108..bc582fbb9a 100644
--- a/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_autoware_api_component.launch.xml
@@ -1,7 +1,8 @@
-
-
+
+
+
diff --git a/autoware_launch/launch/components/tier4_system_component.launch.xml b/autoware_launch/launch/components/tier4_system_component.launch.xml
index 5bb8403dc2..fa5056b9d9 100644
--- a/autoware_launch/launch/components/tier4_system_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_system_component.launch.xml
@@ -28,4 +28,11 @@
+
+
+
+
+
+
+
diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz
index c53d5d62e6..589c9cbfd5 100644
--- a/autoware_launch/rviz/autoware.rviz
+++ b/autoware_launch/rviz/autoware.rviz
@@ -269,13 +269,13 @@ Visualization Manager:
Enabled: true
Name: Vehicle
- Class: rviz_plugins/MrmSummaryOverlayDisplay
- Enabled: false
+ Enabled: true
Font Size: 10
- Left: 512
+ Left: 10
Max Letter Num: 100
Name: MRM Summary
Text Color: 25; 255; 240
- Top: 64
+ Top: 10
Topic:
Depth: 5
Durability Policy: Volatile