From fdd4276292bd7ac5a032ae7d7d683c42717a5532 Mon Sep 17 00:00:00 2001 From: mitukou1109 Date: Thu, 27 Jun 2024 18:35:05 +0900 Subject: [PATCH] reset to autowarefoundation:main --- autoware_launch/config/planning/preset/default_preset.yaml | 4 ++-- .../planning/scenario_planning/common/common.param.yaml | 2 +- .../behavior_velocity_planner/intersection.param.yaml | 2 +- .../autoware_path_optimizer/path_optimizer.param.yaml | 2 +- .../obstacle_cruise_planner.param.yaml | 2 +- .../system/diagnostic_graph_aggregator/autoware-awsim.yaml | 1 - .../system/diagnostic_graph_aggregator/autoware-main.yaml | 3 --- .../system/diagnostic_graph_aggregator/autoware-psim.yaml | 3 --- .../launch/components/tier4_control_component.launch.xml | 2 +- .../launch/components/tier4_system_component.launch.xml | 7 ------- 10 files changed, 7 insertions(+), 21 deletions(-) diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml index 0ffeeeccf0..5a3139e4c5 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: "true" + default: "false" - 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: "true" + default: "false" # 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 5680a99713..4edbbf2d35 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: 11.1 # max velocity limit [m/s] + max_vel: 4.17 # 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 069f336959..c9ac6aa1a6 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: true + enable: false 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 17a044fb67..db89a81e47 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: false # stop if the ego's trajectory footprint is outside the drivable area + enable_outside_drivable_area_stop: true # 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 c9fa876368..b68395aefc 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 : 5.0 # This is also used as a stop margin [m] + 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] 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/config/system/diagnostic_graph_aggregator/autoware-awsim.yaml b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-awsim.yaml index 7f002b1380..9950acbc7e 100644 --- a/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-awsim.yaml +++ b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-awsim.yaml @@ -3,4 +3,3 @@ files: edits: - { type: remove, path: /autoware/system/duplicated_node_checker } - - { type: remove, path: /autoware/control/emergency_braking } diff --git a/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-main.yaml b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-main.yaml index f35f219df6..42af3f79a3 100644 --- a/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-main.yaml +++ b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-main.yaml @@ -1,5 +1,2 @@ files: - { path: $(find-pkg-share system_diagnostic_monitor)/config/autoware-main.yaml } - -edits: - - { type: remove, path: /autoware/control/emergency_braking } diff --git a/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-psim.yaml b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-psim.yaml index e11f391606..dfc820f93c 100644 --- a/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-psim.yaml +++ b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-psim.yaml @@ -1,5 +1,2 @@ files: - { path: $(find-pkg-share system_diagnostic_monitor)/config/autoware-psim.yaml } - -edits: - - { type: remove, path: /autoware/control/emergency_braking } diff --git a/autoware_launch/launch/components/tier4_control_component.launch.xml b/autoware_launch/launch/components/tier4_control_component.launch.xml index 09b817b149..965006a50d 100644 --- a/autoware_launch/launch/components/tier4_control_component.launch.xml +++ b/autoware_launch/launch/components/tier4_control_component.launch.xml @@ -4,7 +4,7 @@ - + diff --git a/autoware_launch/launch/components/tier4_system_component.launch.xml b/autoware_launch/launch/components/tier4_system_component.launch.xml index 6fda11ac7a..d5082a91e8 100644 --- a/autoware_launch/launch/components/tier4_system_component.launch.xml +++ b/autoware_launch/launch/components/tier4_system_component.launch.xml @@ -34,11 +34,4 @@ - - - - - - -