From 569922cd7a010fe5cc619049db66af07e60d1275 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 15 Jan 2024 00:25:32 +0900 Subject: [PATCH 01/16] feat: use obstacle_cruise_planner and change safe_distance_margin Signed-off-by: Takayuki Murooka --- autoware_launch/config/planning/preset/default_preset.yaml | 2 +- .../obstacle_cruise_planner/obstacle_cruise_planner.param.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml index 7bd3dd26b3..8954026761 100644 --- a/autoware_launch/config/planning/preset/default_preset.yaml +++ b/autoware_launch/config/planning/preset/default_preset.yaml @@ -94,7 +94,7 @@ launch: - arg: name: motion_stop_planner_type - default: obstacle_stop_planner + default: obstacle_cruise_planner # option: obstacle_stop_planner # obstacle_cruise_planner # none 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..4d38226c26 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 : 6.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] From 40935760292c21974bd17e70438dec137c1ace54 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 15 Jan 2024 00:26:09 +0900 Subject: [PATCH 02/16] feat: set max_vel to 40km/h Signed-off-by: Takayuki Murooka --- .../motion_velocity_smoother.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 235c76a5c1..44450b1848 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 @@ -1,7 +1,7 @@ /**: ros__parameters: # motion state constraints - max_velocity: 20.0 # max velocity limit [m/s] + max_velocity: 11.1 # max velocity limit [m/s] stop_decel: 0.0 # deceleration at a stop point[m/ss] # external velocity limit parameter From df2779015b1b807ce70a4a62487d885c4156be6a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 16 Jan 2024 11:31:15 +0900 Subject: [PATCH 03/16] feat: enable surround_obstacle_checker Signed-off-by: Takayuki Murooka --- .../launch/components/tier4_planning_component.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml index 06740146f5..a6b5744f1b 100644 --- a/autoware_launch/launch/components/tier4_planning_component.launch.xml +++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml @@ -8,7 +8,7 @@ - + From 39191f2dc0b589c61a592303f1cca8fd73a19200 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 16 Jan 2024 16:13:18 +0900 Subject: [PATCH 04/16] feat: enable surround_obstacle_checker Signed-off-by: Takayuki Murooka --- autoware_launch/config/planning/preset/default_preset.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml index b57696d324..7c4b452bbf 100644 --- a/autoware_launch/config/planning/preset/default_preset.yaml +++ b/autoware_launch/config/planning/preset/default_preset.yaml @@ -112,7 +112,7 @@ launch: - arg: name: launch_surround_obstacle_checker - default: "false" + default: "true" # parking modules - arg: From 1e6387a7bdfd1c00afa9a727d68d122d1d766ba6 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 22 Jan 2024 02:04:51 +0900 Subject: [PATCH 05/16] feat: enable dynamic_avoidance and disable outside_drivable_area_stop Signed-off-by: Takayuki Murooka --- autoware_launch/config/planning/preset/default_preset.yaml | 2 +- .../obstacle_avoidance_planner.param.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml index 7c4b452bbf..72921af441 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_avoidance_module - default: "false" + default: "true" - arg: name: launch_lane_change_right_module default: "true" 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 db89a81e47..17a044fb67 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 @@ -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: From 45bb96c523138405c90f533b007f22968994c7af Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 6 Mar 2024 22:47:49 +0900 Subject: [PATCH 06/16] feat: disable AEB and set the maximum velocity to 40km/h Signed-off-by: Takayuki Murooka --- .../config/planning/scenario_planning/common/common.param.yaml | 2 +- .../launch/components/tier4_control_component.launch.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) 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 0dba945718..face8610c7 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/launch/components/tier4_control_component.launch.xml b/autoware_launch/launch/components/tier4_control_component.launch.xml index 5c3cf06ad0..d15e050d7a 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 @@ - + From ae6d0bb952374ac38ff6752dcc69a0827b0a6d68 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 19 Mar 2024 23:53:45 +0900 Subject: [PATCH 07/16] enable intersection_occlusion detection Signed-off-by: Mamoru Sobue --- .../behavior_velocity_planner/intersection.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 68d4070cbf..abd12a9470 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 From a26f6b7e3f444b74f496d7e788a2d4fe39d1bdd3 Mon Sep 17 00:00:00 2001 From: mitukou1109 Date: Thu, 2 May 2024 14:26:51 +0900 Subject: [PATCH 08/16] add parameters for obstacle_cruise_planner --- .../obstacle_cruise_planner.param.yaml | 5 +++++ 1 file changed, 5 insertions(+) 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 dc314511a1..86f6f95200 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 @@ -37,6 +37,7 @@ motorcycle: true bicycle: true pedestrian: true + pointcloud: false cruise_obstacle_type: inside: @@ -68,8 +69,12 @@ motorcycle: true bicycle: true pedestrian: true + pointcloud: false behavior_determination: + use_pointcloud: false + pointcloud_search_radius: 5.0 + decimate_trajectory_step_length : 2.0 # longitudinal step length to calculate trajectory polygon for collision checking prediction_resampling_time_interval: 0.1 From 1c5c362ced8c511c527f871480731146612064e3 Mon Sep 17 00:00:00 2001 From: mitukou1109 Date: Wed, 8 May 2024 12:20:10 +0900 Subject: [PATCH 09/16] add parameters for pointcloud filtering --- .../obstacle_cruise_planner.param.yaml | 6 ++++++ 1 file changed, 6 insertions(+) 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 86f6f95200..8dcd81f2fc 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 @@ -74,6 +74,12 @@ behavior_determination: use_pointcloud: false pointcloud_search_radius: 5.0 + pointcloud_voxel_grid_x: 0.05 + pointcloud_voxel_grid_y: 0.05 + pointcloud_voxel_grid_z: 100000.0 + pointcloud_cluster_tolerance: 1.0 + pointcloud_min_cluster_size: 1 + pointcloud_max_cluster_size: 100000 decimate_trajectory_step_length : 2.0 # longitudinal step length to calculate trajectory polygon for collision checking From d8b1c9199fe76bc85213d54d9fd92b33bb136fbe Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 3 Jun 2024 21:16:19 +0900 Subject: [PATCH 10/16] chore(planning_launch): update motion module name (#1014) Signed-off-by: satoshi-ota --- .../config/planning/preset/default_preset.yaml | 6 +++--- .../Analytical.param.yaml | 0 .../JerkFiltered.param.yaml | 0 .../L2.param.yaml | 0 .../Linf.param.yaml | 0 .../velocity_smoother.param.yaml} | 0 .../path_optimizer.param.yaml} | 0 .../components/tier4_planning_component.launch.xml | 13 ++++++++----- autoware_launch/rviz/autoware.rviz | 2 +- 9 files changed, 12 insertions(+), 9 deletions(-) rename autoware_launch/config/planning/scenario_planning/common/{motion_velocity_smoother => autoware_velocity_smoother}/Analytical.param.yaml (100%) rename autoware_launch/config/planning/scenario_planning/common/{motion_velocity_smoother => autoware_velocity_smoother}/JerkFiltered.param.yaml (100%) rename autoware_launch/config/planning/scenario_planning/common/{motion_velocity_smoother => autoware_velocity_smoother}/L2.param.yaml (100%) rename autoware_launch/config/planning/scenario_planning/common/{motion_velocity_smoother => autoware_velocity_smoother}/Linf.param.yaml (100%) rename autoware_launch/config/planning/scenario_planning/common/{motion_velocity_smoother/motion_velocity_smoother.param.yaml => autoware_velocity_smoother/velocity_smoother.param.yaml} (100%) rename autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/{obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml => autoware_path_optimizer/path_optimizer.param.yaml} (100%) diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml index 82fbd43399..55c9de67ad 100644 --- a/autoware_launch/config/planning/preset/default_preset.yaml +++ b/autoware_launch/config/planning/preset/default_preset.yaml @@ -93,8 +93,8 @@ launch: - arg: name: motion_path_planner_type - default: obstacle_avoidance_planner - # option: obstacle_avoidance_planner + default: path_optimizer + # option: path_optimizer # path_sampler # none @@ -111,7 +111,7 @@ launch: # none - arg: - name: motion_velocity_smoother_type + name: velocity_smoother_type default: JerkFiltered # option: JerkFiltered # L2 diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml b/autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/Analytical.param.yaml similarity index 100% rename from autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Analytical.param.yaml rename to autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/Analytical.param.yaml diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml b/autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/JerkFiltered.param.yaml similarity index 100% rename from autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/JerkFiltered.param.yaml rename to autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/JerkFiltered.param.yaml diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/L2.param.yaml b/autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/L2.param.yaml similarity index 100% rename from autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/L2.param.yaml rename to autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/L2.param.yaml diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml b/autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/Linf.param.yaml similarity index 100% rename from autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/Linf.param.yaml rename to autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/Linf.param.yaml 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/autoware_velocity_smoother/velocity_smoother.param.yaml similarity index 100% rename from autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml rename to autoware_launch/config/planning/scenario_planning/common/autoware_velocity_smoother/velocity_smoother.param.yaml 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/autoware_path_optimizer/path_optimizer.param.yaml similarity index 100% rename from autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/autoware_path_optimizer/path_optimizer.param.yaml diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml index c9f4e2ceae..5a48ea8908 100644 --- a/autoware_launch/launch/components/tier4_planning_component.launch.xml +++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml @@ -43,7 +43,7 @@ - + @@ -68,7 +68,7 @@ - + @@ -77,11 +77,14 @@ - + - - + + diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 627d9e8923..5e7cba18cf 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -2127,7 +2127,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/scenario_planning/motion_velocity_smoother/virtual_wall + Value: /planning/scenario_planning/velocity_smoother/virtual_wall Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true From 23d87187c583156d6c5ac5d5b0d33c27f54a366b Mon Sep 17 00:00:00 2001 From: mitukou1109 Date: Wed, 12 Jun 2024 16:27:36 +0900 Subject: [PATCH 11/16] move use_pointcloud to common parameter --- .../obstacle_cruise_planner/obstacle_cruise_planner.param.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) 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 c5318b9568..20620d37a9 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 @@ -6,6 +6,8 @@ enable_debug_info: false enable_calculation_time_info: false + use_pointcloud: true + enable_slow_down_planning: true # longitudinal info @@ -72,7 +74,6 @@ pointcloud: false behavior_determination: - use_pointcloud: false pointcloud_search_radius: 5.0 pointcloud_voxel_grid_x: 0.05 pointcloud_voxel_grid_y: 0.05 From 3a58c2554e7fce7cb2356f41efb724aef1e472cf Mon Sep 17 00:00:00 2001 From: mitukou1109 Date: Wed, 19 Jun 2024 18:31:27 +0900 Subject: [PATCH 12/16] disable using pointcloud by default --- .../obstacle_cruise_planner/obstacle_cruise_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 20620d37a9..1d08b75a28 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 @@ -6,7 +6,7 @@ enable_debug_info: false enable_calculation_time_info: false - use_pointcloud: true + use_pointcloud: false enable_slow_down_planning: true From 2fd46d00be5c8265243247cd4815bdc25ee9ac79 Mon Sep 17 00:00:00 2001 From: Daniel Sanchez Date: Thu, 20 Jun 2024 10:09:27 +0900 Subject: [PATCH 13/16] disable AEB diag check Signed-off-by: Daniel Sanchez --- .../system/diagnostic_graph_aggregator/autoware-awsim.yaml | 1 + .../system/diagnostic_graph_aggregator/autoware-main.yaml | 3 +++ .../system/diagnostic_graph_aggregator/autoware-psim.yaml | 3 +++ 3 files changed, 7 insertions(+) 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 9950acbc7e..7f002b1380 100644 --- a/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-awsim.yaml +++ b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-awsim.yaml @@ -3,3 +3,4 @@ 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 42af3f79a3..f35f219df6 100644 --- a/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-main.yaml +++ b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-main.yaml @@ -1,2 +1,5 @@ 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 dfc820f93c..e11f391606 100644 --- a/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-psim.yaml +++ b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-psim.yaml @@ -1,2 +1,5 @@ files: - { path: $(find-pkg-share system_diagnostic_monitor)/config/autoware-psim.yaml } + +edits: + - { type: remove, path: /autoware/control/emergency_braking } From 40a87e1f8342031f62bbde5b106c59a048aa4e70 Mon Sep 17 00:00:00 2001 From: mitukou1109 Date: Thu, 20 Jun 2024 14:07:22 +0900 Subject: [PATCH 14/16] remove use_pointcloud parameter --- .../obstacle_cruise_planner/obstacle_cruise_planner.param.yaml | 2 -- 1 file changed, 2 deletions(-) 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 1d08b75a28..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 @@ -6,8 +6,6 @@ enable_debug_info: false enable_calculation_time_info: false - use_pointcloud: false - enable_slow_down_planning: true # longitudinal info From 321cffa4237a625acaa04637ba64799fe06c3222 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 20 Jun 2024 15:16:34 +0900 Subject: [PATCH 15/16] feat(diagnostic_graph_utils): launch logging node for diagnostic_graph Signed-off-by: Takamasa Horibe --- .../launch/components/tier4_system_component.launch.xml | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/autoware_launch/launch/components/tier4_system_component.launch.xml b/autoware_launch/launch/components/tier4_system_component.launch.xml index d5082a91e8..6fda11ac7a 100644 --- a/autoware_launch/launch/components/tier4_system_component.launch.xml +++ b/autoware_launch/launch/components/tier4_system_component.launch.xml @@ -34,4 +34,11 @@ + + + + + + + From fdd4276292bd7ac5a032ae7d7d683c42717a5532 Mon Sep 17 00:00:00 2001 From: mitukou1109 Date: Thu, 27 Jun 2024 18:35:05 +0900 Subject: [PATCH 16/16] 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 @@ - - - - - - -