diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml index 674b3e07e7..fb2e3f2191 100644 --- a/autoware_launch/config/planning/preset/default_preset.yaml +++ b/autoware_launch/config/planning/preset/default_preset.yaml @@ -121,3 +121,9 @@ launch: - arg: name: launch_parking_module default: "true" + + # auto parking module, needs launch_parking_module + - arg: + name: launch_avp_module + default: "true" + diff --git a/autoware_launch/config/planning/scenario_planning/parking/auto_parking/auto_parking.param.yaml b/autoware_launch/config/planning/scenario_planning/parking/auto_parking/auto_parking.param.yaml new file mode 100644 index 0000000000..6d7812f4c3 --- /dev/null +++ b/autoware_launch/config/planning/scenario_planning/parking/auto_parking/auto_parking.param.yaml @@ -0,0 +1,31 @@ +/**: + ros__parameters: + # -- Auto Park Node Configurations -- + th_arrived_distance_m: 1.0 + th_parking_space_distance_m: 10.0 + update_rate: 5.0 + vehicle_shape_margin_m: 0.2 + + # -- Configurations common to the all planners -- + # base configs + time_limit: 30000.0 + minimum_turning_radius: 5.0 + maximum_turning_radius: 9.0 + turning_radius_size: 3 + # search configs + theta_size: 144 + angle_goal_range: 6.0 + curve_weight: 1.2 + reverse_weight: 2.0 + lateral_goal_range: 0.5 + longitudinal_goal_range: 2.0 + # costmap configs + obstacle_threshold: 100 + + # -- A* search Configurations -- + astar: + only_behind_solutions: false + use_back: true + use_curve_weight: false + use_complete_astar: true + distance_heuristic_weight: 1.0 \ No newline at end of file diff --git a/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml index 93c9e235dd..2dc15b71c0 100644 --- a/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml @@ -8,7 +8,7 @@ th_stopped_time_sec: 1.0 th_stopped_velocity_mps: 0.01 th_course_out_distance_m: 1.0 - vehicle_shape_margin_m: 1.0 + vehicle_shape_margin_m: 0.5 replan_when_obstacle_found: true replan_when_course_out: true @@ -19,9 +19,9 @@ robot_length: 4.5 robot_width: 1.75 robot_base2back: 1.0 - minimum_turning_radius: 9.0 + minimum_turning_radius: 5.0 maximum_turning_radius: 9.0 - turning_radius_size: 1 + turning_radius_size: 3 # search configs theta_size: 144 angle_goal_range: 6.0 @@ -47,3 +47,4 @@ max_planning_time: 150.0 neighbor_radius: 8.0 margin: 0.1 + diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml index f093ce8133..c2972d3dc3 100644 --- a/autoware_launch/launch/components/tier4_planning_component.launch.xml +++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml @@ -59,6 +59,9 @@ + + +