@@ -981,63 +981,14 @@ BehaviorModuleOutput GoalPlannerModule::plan()
981
981
return fixed_goal_planner_->plan (planner_data_);
982
982
}
983
983
984
- std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath (
985
- const PullOverContextData & context_data ,
984
+ void sortPullOverPaths (
985
+ const std::shared_ptr< const PlannerData> planner_data, const GoalPlannerParameters & parameters ,
986
986
const std::vector<PullOverPath> & pull_over_path_candidates,
987
- const GoalCandidates & goal_candidates) const
987
+ const GoalCandidates & goal_candidates, const PredictedObjects & static_target_objects,
988
+ rclcpp::Logger logger, std::vector<size_t > & sorted_path_indices)
988
989
{
989
- universe_utils::ScopedTimeTrack st (__func__, *time_keeper_);
990
-
991
- const auto & goal_pose = planner_data_->route_handler ->getOriginalGoalPose ();
992
- const double backward_length =
993
- parameters_->backward_goal_search_length + parameters_->decide_path_distance ;
994
- const auto & prev_module_output_path = getPreviousModuleOutput ().path ;
995
- const auto & soft_margins = parameters_->object_recognition_collision_check_soft_margins ;
996
- const auto & hard_margins = parameters_->object_recognition_collision_check_hard_margins ;
997
-
998
- // STEP1: Filter valid paths before sorting
999
- // NOTE: Since copying pull over path takes time, it is handled by indices
1000
- std::vector<size_t > sorted_path_indices;
1001
- sorted_path_indices.reserve (pull_over_path_candidates.size ());
1002
-
1003
- // STEP1-1: Extract paths which have safe goal
1004
- // Create a map of goal_id to GoalCandidate for quick access
1005
- std::unordered_map<int , GoalCandidate> goal_candidate_map;
1006
- for (const auto & goal_candidate : goal_candidates) {
1007
- goal_candidate_map[goal_candidate.id ] = goal_candidate;
1008
- }
1009
- for (size_t i = 0 ; i < pull_over_path_candidates.size (); ++i) {
1010
- const auto & path = pull_over_path_candidates[i];
1011
- const auto goal_candidate_it = goal_candidate_map.find (path.goal_id ());
1012
- if (goal_candidate_it != goal_candidate_map.end () && goal_candidate_it->second .is_safe ) {
1013
- sorted_path_indices.push_back (i);
1014
- }
1015
- }
1016
-
1017
- // STEP1-2: Remove paths which do not have enough distance
1018
- const double prev_path_front_to_goal_dist = calcSignedArcLength (
1019
- prev_module_output_path.points , prev_module_output_path.points .front ().point .pose .position ,
1020
- goal_pose.position );
1021
- const auto & long_tail_reference_path = [&]() {
1022
- if (prev_path_front_to_goal_dist > backward_length) {
1023
- return prev_module_output_path;
1024
- }
1025
- // get road lanes which is at least backward_length[m] behind the goal
1026
- const auto road_lanes = utils::getExtendedCurrentLanesFromPath (
1027
- prev_module_output_path, planner_data_, backward_length, 0.0 , false );
1028
- const auto goal_pose_length = lanelet::utils::getArcCoordinates (road_lanes, goal_pose).length ;
1029
- return planner_data_->route_handler ->getCenterLinePath (
1030
- road_lanes, std::max (0.0 , goal_pose_length - backward_length),
1031
- goal_pose_length + parameters_->forward_goal_search_length );
1032
- }();
1033
-
1034
- sorted_path_indices.erase (
1035
- std::remove_if (
1036
- sorted_path_indices.begin (), sorted_path_indices.end (),
1037
- [&](const size_t i) {
1038
- return !hasEnoughDistance (pull_over_path_candidates[i], long_tail_reference_path);
1039
- }),
1040
- sorted_path_indices.end ());
990
+ const auto & soft_margins = parameters.object_recognition_collision_check_soft_margins ;
991
+ const auto & hard_margins = parameters.object_recognition_collision_check_hard_margins ;
1041
992
1042
993
// STEP2: Sort pull over path candidates
1043
994
// STEP2-1: Sort pull_over_path_candidates based on the order in goal_candidates
@@ -1065,14 +1016,14 @@ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(
1065
1016
1066
1017
// compare to sort pull_over_path_candidates based on the order in efficient_path_order
1067
1018
const auto comparePathTypePriority = [&](const PullOverPath & a, const PullOverPath & b) -> bool {
1068
- const auto & order = parameters_-> efficient_path_order ;
1019
+ const auto & order = parameters. efficient_path_order ;
1069
1020
const auto a_pos = std::find (order.begin (), order.end (), magic_enum::enum_name (a.type ()));
1070
1021
const auto b_pos = std::find (order.begin (), order.end (), magic_enum::enum_name (b.type ()));
1071
1022
return a_pos < b_pos;
1072
1023
};
1073
1024
1074
1025
// if object recognition is enabled, sort by collision check margin
1075
- if (parameters_-> use_object_recognition ) {
1026
+ if (parameters. use_object_recognition ) {
1076
1027
// STEP2-2: Sort by collision check margins
1077
1028
const auto [margins, margins_with_zero] =
1078
1029
std::invoke ([&]() -> std::tuple<std::vector<double >, std::vector<double >> {
@@ -1085,11 +1036,11 @@ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(
1085
1036
1086
1037
// Create a map of PullOverPath pointer to largest collision check margin
1087
1038
std::map<size_t , double > path_id_to_rough_margin_map;
1088
- const auto & target_objects = context_data. static_target_objects ;
1039
+ const auto & target_objects = static_target_objects;
1089
1040
for (const size_t i : sorted_path_indices) {
1090
1041
const auto & path = pull_over_path_candidates[i];
1091
1042
const double distance = utils::path_safety_checker::calculateRoughDistanceToObjects (
1092
- path.parking_path (), target_objects, planner_data_ ->parameters , false , " max" );
1043
+ path.parking_path (), target_objects, planner_data ->parameters , false , " max" );
1093
1044
auto it = std::lower_bound (
1094
1045
margins_with_zero.begin (), margins_with_zero.end (), distance, std::greater<double >());
1095
1046
if (it == margins_with_zero.end ()) {
@@ -1119,7 +1070,7 @@ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(
1119
1070
// STEP2-3: Sort by curvature
1120
1071
// If the curvature is less than the threshold, prioritize the path.
1121
1072
const auto isHighCurvature = [&](const PullOverPath & path) -> bool {
1122
- return path.parking_path_max_curvature () >= parameters_-> high_curvature_threshold ;
1073
+ return path.parking_path_max_curvature () >= parameters. high_curvature_threshold ;
1123
1074
};
1124
1075
1125
1076
const auto isSoftMargin = [&](const PullOverPath & path) -> bool {
@@ -1155,7 +1106,7 @@ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(
1155
1106
1156
1107
// STEP2-4: Sort pull_over_path_candidates based on the order in efficient_path_order keeping
1157
1108
// the collision check margin and curvature priority.
1158
- if (parameters_-> path_priority == " efficient_path" ) {
1109
+ if (parameters. path_priority == " efficient_path" ) {
1159
1110
std::stable_sort (
1160
1111
sorted_path_indices.begin (), sorted_path_indices.end (),
1161
1112
[&](const size_t a_i, const size_t b_i) {
@@ -1182,14 +1133,14 @@ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(
1182
1133
const std::string path_priority_info_str = goal_planner_utils::makePathPriorityDebugMessage (
1183
1134
sorted_path_indices, pull_over_path_candidates, goal_id_to_index, goal_candidates,
1184
1135
path_id_to_rough_margin_map, isSoftMargin, isHighCurvature);
1185
- RCLCPP_DEBUG_STREAM (getLogger () , path_priority_info_str);
1136
+ RCLCPP_DEBUG_STREAM (logger , path_priority_info_str);
1186
1137
} else {
1187
1138
/* *
1188
1139
* NOTE: use_object_recognition=false is not recommended. This option will be deprecated in the
1189
1140
* future. sort by curvature is not implemented yet.
1190
1141
* Sort pull_over_path_candidates based on the order in efficient_path_order
1191
1142
*/
1192
- if (parameters_-> path_priority == " efficient_path" ) {
1143
+ if (parameters. path_priority == " efficient_path" ) {
1193
1144
std::stable_sort (
1194
1145
sorted_path_indices.begin (), sorted_path_indices.end (),
1195
1146
[&](const size_t a_i, const size_t b_i) {
@@ -1202,6 +1153,67 @@ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath(
1202
1153
});
1203
1154
}
1204
1155
}
1156
+ }
1157
+
1158
+ std::optional<PullOverPath> GoalPlannerModule::selectPullOverPath (
1159
+ const PullOverContextData & context_data,
1160
+ const std::vector<PullOverPath> & pull_over_path_candidates,
1161
+ const GoalCandidates & goal_candidates) const
1162
+ {
1163
+ universe_utils::ScopedTimeTrack st (__func__, *time_keeper_);
1164
+
1165
+ const auto & goal_pose = planner_data_->route_handler ->getOriginalGoalPose ();
1166
+ const double backward_length =
1167
+ parameters_->backward_goal_search_length + parameters_->decide_path_distance ;
1168
+ const auto & prev_module_output_path = getPreviousModuleOutput ().path ;
1169
+
1170
+ // STEP1: Filter valid paths before sorting
1171
+ // NOTE: Since copying pull over path takes time, it is handled by indices
1172
+ std::vector<size_t > sorted_path_indices;
1173
+ sorted_path_indices.reserve (pull_over_path_candidates.size ());
1174
+
1175
+ // STEP1-1: Extract paths which have safe goal
1176
+ // Create a map of goal_id to GoalCandidate for quick access
1177
+ std::unordered_map<int , GoalCandidate> goal_candidate_map;
1178
+ for (const auto & goal_candidate : goal_candidates) {
1179
+ goal_candidate_map[goal_candidate.id ] = goal_candidate;
1180
+ }
1181
+ for (size_t i = 0 ; i < pull_over_path_candidates.size (); ++i) {
1182
+ const auto & path = pull_over_path_candidates[i];
1183
+ const auto goal_candidate_it = goal_candidate_map.find (path.goal_id ());
1184
+ if (goal_candidate_it != goal_candidate_map.end () && goal_candidate_it->second .is_safe ) {
1185
+ sorted_path_indices.push_back (i);
1186
+ }
1187
+ }
1188
+
1189
+ // STEP1-2: Remove paths which do not have enough distance
1190
+ const double prev_path_front_to_goal_dist = calcSignedArcLength (
1191
+ prev_module_output_path.points , prev_module_output_path.points .front ().point .pose .position ,
1192
+ goal_pose.position );
1193
+ const auto & long_tail_reference_path = [&]() {
1194
+ if (prev_path_front_to_goal_dist > backward_length) {
1195
+ return prev_module_output_path;
1196
+ }
1197
+ // get road lanes which is at least backward_length[m] behind the goal
1198
+ const auto road_lanes = utils::getExtendedCurrentLanesFromPath (
1199
+ prev_module_output_path, planner_data_, backward_length, 0.0 , false );
1200
+ const auto goal_pose_length = lanelet::utils::getArcCoordinates (road_lanes, goal_pose).length ;
1201
+ return planner_data_->route_handler ->getCenterLinePath (
1202
+ road_lanes, std::max (0.0 , goal_pose_length - backward_length),
1203
+ goal_pose_length + parameters_->forward_goal_search_length );
1204
+ }();
1205
+
1206
+ sorted_path_indices.erase (
1207
+ std::remove_if (
1208
+ sorted_path_indices.begin (), sorted_path_indices.end (),
1209
+ [&](const size_t i) {
1210
+ return !hasEnoughDistance (pull_over_path_candidates[i], long_tail_reference_path);
1211
+ }),
1212
+ sorted_path_indices.end ());
1213
+
1214
+ sortPullOverPaths (
1215
+ planner_data_, *parameters_, pull_over_path_candidates, goal_candidates,
1216
+ context_data.static_target_objects , getLogger (), sorted_path_indices);
1205
1217
1206
1218
// STEP3: Select the final pull over path by checking collision to make it as high priority as
1207
1219
// possible
0 commit comments