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 fe30397683..a05bdda099 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
@@ -42,7 +42,6 @@
max_object_angle: 0.785
drivable_area_generation:
- polygon_generation_method: "object_path_base" # choose "ego_path_base" and "object_path_base"
object_path_base:
min_longitudinal_polygon_margin: 3.0 # [m]
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..0c12624f3b 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
@@ -42,7 +42,13 @@
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
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..00df2e2ced 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
@@ -14,8 +14,7 @@
consider_wrong_direction_vehicle: false
stuck_vehicle:
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
@@ -48,6 +47,7 @@
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]
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
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..251486dafd 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,7 @@
/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/vehicle/node_alive_monitoring: default
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index 65b8ac20bd..cf5b2dd98c 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -93,5 +93,9 @@
+
+
+
+
diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz
index 915a296d79..296d707b13 100644
--- a/autoware_launch/rviz/autoware.rviz
+++ b/autoware_launch/rviz/autoware.rviz
@@ -2418,6 +2418,34 @@ 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
+ Displays: ~
+ Enabled: true
+ Name: Localization
+ - 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