diff --git a/planning/autoware_path_generator/config/path_generator.param.yaml b/planning/autoware_path_generator/config/path_generator.param.yaml index 1a8d2c6c57..b6ed2383e3 100644 --- a/planning/autoware_path_generator/config/path_generator.param.yaml +++ b/planning/autoware_path_generator/config/path_generator.param.yaml @@ -1,7 +1,9 @@ /**: ros__parameters: planning_hz: 10.0 - backward_path_length: 5.0 - forward_path_length: 300.0 - waypoint_group_separation_threshold: 1.0 - waypoint_group_interval_margin_ratio: 10.0 + path_length: + backward: 5.0 + forward: 300.0 + waypoint_group: + separation_threshold: 1.0 + interval_margin_ratio: 10.0 diff --git a/planning/autoware_path_generator/param/path_generator_parameters.yaml b/planning/autoware_path_generator/param/path_generator_parameters.yaml index 8d9f77a777..2c7192427b 100644 --- a/planning/autoware_path_generator/param/path_generator_parameters.yaml +++ b/planning/autoware_path_generator/param/path_generator_parameters.yaml @@ -2,14 +2,16 @@ path_generator: planning_hz: type: double - backward_path_length: - type: double + path_length: + backward: + type: double - forward_path_length: - type: double + forward: + type: double - waypoint_group_separation_threshold: - type: double + waypoint_group: + separation_threshold: + type: double - waypoint_group_interval_margin_ratio: - type: double + interval_margin_ratio: + type: double diff --git a/planning/autoware_path_generator/src/node.cpp b/planning/autoware_path_generator/src/node.cpp index 11b2a3764e..18eff123d6 100644 --- a/planning/autoware_path_generator/src/node.cpp +++ b/planning/autoware_path_generator/src/node.cpp @@ -208,8 +208,8 @@ std::optional PathGenerator::generate_path( } const auto lanelets = utils::get_lanelets_within_route( - current_lane, planner_data_, current_pose, params.backward_path_length, - params.forward_path_length); + current_lane, planner_data_, current_pose, params.path_length.backward, + params.path_length.forward); if (!lanelets) { return std::nullopt; } @@ -229,9 +229,9 @@ std::optional PathGenerator::generate_path( const auto arc_coordinates = lanelet::utils::getArcCoordinates(lanelets, current_pose); const auto s = arc_coordinates.length; // s denotes longitudinal position in Frenet coordinates - const auto s_start = std::max(0., s - params.backward_path_length); + const auto s_start = std::max(0., s - params.path_length.backward); const auto s_end = [&]() { - auto s_end = s + params.forward_path_length; + auto s_end = s + params.path_length.forward; if (!utils::get_next_lanelet_within_route(lanelets.back(), planner_data_)) { s_end = std::min(s_end, lanelet::utils::getLaneletLength2d(lanelets)); @@ -268,8 +268,8 @@ std::optional PathGenerator::generate_path( }; const auto waypoint_groups = utils::get_waypoint_groups( - lanelet_sequence, *planner_data_.lanelet_map_ptr, params.waypoint_group_separation_threshold, - params.waypoint_group_interval_margin_ratio); + lanelet_sequence, *planner_data_.lanelet_map_ptr, params.waypoint_group.separation_threshold, + params.waypoint_group.interval_margin_ratio); auto extended_lanelets = lanelet_sequence.lanelets(); auto s_offset = 0.;