Skip to content

Commit 27ba413

Browse files
kyoichi-sugaharakarishma1911
authored andcommitted
feat(start_planner): define collision check margin as list (autowarefoundation#5994)
* define collision check margins list in start planner module Signed-off-by: kyoichi-sugahara <[email protected]> --------- Signed-off-by: kyoichi-sugahara <[email protected]>
1 parent a5f3d87 commit 27ba413

File tree

7 files changed

+45
-37
lines changed

7 files changed

+45
-37
lines changed

planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,8 @@ struct StartGoalPlannerData
4141

4242
Pose refined_start_pose;
4343
std::vector<Pose> start_pose_candidates;
44+
size_t selected_start_pose_candidate_index;
45+
double margin_for_start_pose_candidate;
4446
};
4547

4648
} // namespace behavior_path_planner

planning/behavior_path_start_planner_module/README.md

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -65,19 +65,19 @@ PullOutPath --o PullOutPlannerBase
6565

6666
## General parameters for start_planner
6767

68-
| Name | Unit | Type | Description | Default value |
69-
| :---------------------------------------------------------- | :---- | :----- | :-------------------------------------------------------------------------- | :------------ |
70-
| th_arrived_distance_m | [m] | double | distance threshold for arrival of path termination | 1.0 |
71-
| th_distance_to_middle_of_the_road | [m] | double | distance threshold to determine if the vehicle is on the middle of the road | 0.1 |
72-
| th_stopped_velocity_mps | [m/s] | double | velocity threshold for arrival of path termination | 0.01 |
73-
| th_stopped_time_sec | [s] | double | time threshold for arrival of path termination | 1.0 |
74-
| th_turn_signal_on_lateral_offset | [m] | double | lateral distance threshold for turning on blinker | 1.0 |
75-
| intersection_search_length | [m] | double | check if intersections exist within this length | 30.0 |
76-
| length_ratio_for_turn_signal_deactivation_near_intersection | [m] | double | deactivate turn signal of this module near intersection | 0.5 |
77-
| collision_check_margin | [m] | double | Obstacle collision check margin | 1.0 |
78-
| collision_check_distance_from_end | [m] | double | collision check distance from end shift end pose | 1.0 |
79-
| collision_check_margin_from_front_object | [m] | double | collision check margin from front object | 5.0 |
80-
| center_line_path_interval | [m] | double | reference center line path point interval | 1.0 |
68+
| Name | Unit | Type | Description | Default value |
69+
| :---------------------------------------------------------- | :---- | :------- | :-------------------------------------------------------------------------- | :-------------- |
70+
| th_arrived_distance_m | [m] | double | distance threshold for arrival of path termination | 1.0 |
71+
| th_distance_to_middle_of_the_road | [m] | double | distance threshold to determine if the vehicle is on the middle of the road | 0.1 |
72+
| th_stopped_velocity_mps | [m/s] | double | velocity threshold for arrival of path termination | 0.01 |
73+
| th_stopped_time_sec | [s] | double | time threshold for arrival of path termination | 1.0 |
74+
| th_turn_signal_on_lateral_offset | [m] | double | lateral distance threshold for turning on blinker | 1.0 |
75+
| intersection_search_length | [m] | double | check if intersections exist within this length | 30.0 |
76+
| length_ratio_for_turn_signal_deactivation_near_intersection | [m] | double | deactivate turn signal of this module near intersection | 0.5 |
77+
| collision_check_margins | [m] | [double] | Obstacle collision check margins list | [2.0, 1.5, 1.0] |
78+
| collision_check_distance_from_end | [m] | double | collision check distance from end shift end pose | 1.0 |
79+
| collision_check_margin_from_front_object | [m] | double | collision check margin from front object | 5.0 |
80+
| center_line_path_interval | [m] | double | reference center line path point interval | 1.0 |
8181

8282
## Safety check with static obstacles
8383

planning/behavior_path_start_planner_module/config/start_planner.param.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
th_arrived_distance: 1.0
66
th_stopped_velocity: 0.01
77
th_stopped_time: 1.0
8-
collision_check_margin: 1.0
8+
collision_check_margins: [2.0, 1.5, 1.0]
99
collision_check_distance_from_end: 1.0
1010
collision_check_margin_from_front_object: 5.0
1111
th_moving_object_velocity: 1.0

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -172,7 +172,7 @@ class StartPlannerModule : public SceneModuleInterface
172172
const std::string & search_priority, const size_t start_pose_candidates_num);
173173
bool findPullOutPath(
174174
const Pose & start_pose_candidate, const std::shared_ptr<PullOutPlannerBase> & planner,
175-
const Pose & refined_start_pose, const Pose & goal_pose);
175+
const Pose & refined_start_pose, const Pose & goal_pose, const double collision_check_margin);
176176

177177
PathWithLaneId extractCollisionCheckSection(const PullOutPath & path);
178178
void updateStatusWithCurrentPath(

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ struct StartPlannerParameters
4242
double th_distance_to_middle_of_the_road{0.0};
4343
double intersection_search_length{0.0};
4444
double length_ratio_for_turn_signal_deactivation_near_intersection{0.0};
45-
double collision_check_margin{0.0};
45+
std::vector<double> collision_check_margins{};
4646
double collision_check_distance_from_end{0.0};
4747
double collision_check_margin_from_front_object{0.0};
4848
double th_moving_object_velocity{0.0};

planning/behavior_path_start_planner_module/src/manager.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,8 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
4343
p.intersection_search_length = node->declare_parameter<double>(ns + "intersection_search_length");
4444
p.length_ratio_for_turn_signal_deactivation_near_intersection = node->declare_parameter<double>(
4545
ns + "length_ratio_for_turn_signal_deactivation_near_intersection");
46-
p.collision_check_margin = node->declare_parameter<double>(ns + "collision_check_margin");
46+
p.collision_check_margins =
47+
node->declare_parameter<std::vector<double>>(ns + "collision_check_margins");
4748
p.collision_check_distance_from_end =
4849
node->declare_parameter<double>(ns + "collision_check_distance_from_end");
4950
p.collision_check_margin_from_front_object =

planning/behavior_path_start_planner_module/src/start_planner_module.cpp

Lines changed: 25 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -584,9 +584,16 @@ void StartPlannerModule::planWithPriority(
584584
const PriorityOrder order_priority =
585585
determinePriorityOrder(search_priority, start_pose_candidates.size());
586586

587-
for (const auto & [index, planner] : order_priority) {
588-
if (findPullOutPath(start_pose_candidates[index], planner, refined_start_pose, goal_pose))
589-
return;
587+
for (const auto & collision_check_margin : parameters_->collision_check_margins) {
588+
for (const auto & [index, planner] : order_priority) {
589+
if (findPullOutPath(
590+
start_pose_candidates[index], planner, refined_start_pose, goal_pose,
591+
collision_check_margin)) {
592+
start_planner_data_.selected_start_pose_candidate_index = index;
593+
start_planner_data_.margin_for_start_pose_candidate = collision_check_margin;
594+
return;
595+
}
596+
}
590597
}
591598

592599
updateStatusIfNoSafePathFound();
@@ -617,7 +624,7 @@ PriorityOrder StartPlannerModule::determinePriorityOrder(
617624

618625
bool StartPlannerModule::findPullOutPath(
619626
const Pose & start_pose_candidate, const std::shared_ptr<PullOutPlannerBase> & planner,
620-
const Pose & refined_start_pose, const Pose & goal_pose)
627+
const Pose & refined_start_pose, const Pose & goal_pose, const double collision_check_margin)
621628
{
622629
const auto & dynamic_objects = planner_data_->dynamic_object;
623630
const auto pull_out_lanes = start_planner_utils::getPullOutLanes(
@@ -645,7 +652,7 @@ bool StartPlannerModule::findPullOutPath(
645652
// check collision
646653
if (utils::checkCollisionBetweenPathFootprintsAndObjects(
647654
vehicle_footprint, extractCollisionCheckSection(*pull_out_path), pull_out_lane_stop_objects,
648-
parameters_->collision_check_margin)) {
655+
collision_check_margin)) {
649656
return false;
650657
}
651658

@@ -666,23 +673,21 @@ PathWithLaneId StartPlannerModule::extractCollisionCheckSection(const PullOutPat
666673
combined_path.points.insert(
667674
combined_path.points.end(), partial_path.points.begin(), partial_path.points.end());
668675
}
669-
670676
// calculate collision check end idx
671-
size_t collision_check_end_idx = 0;
672-
const auto collision_check_end_pose = motion_utils::calcLongitudinalOffsetPose(
673-
combined_path.points, path.end_pose.position, parameters_->collision_check_distance_from_end);
674-
675-
if (collision_check_end_pose) {
676-
collision_check_end_idx =
677-
motion_utils::findNearestIndex(combined_path.points, collision_check_end_pose->position);
678-
}
677+
const size_t collision_check_end_idx = std::invoke([&]() {
678+
const auto collision_check_end_pose = motion_utils::calcLongitudinalOffsetPose(
679+
combined_path.points, path.end_pose.position, parameters_->collision_check_distance_from_end);
679680

681+
if (collision_check_end_pose) {
682+
return motion_utils::findNearestIndex(
683+
combined_path.points, collision_check_end_pose->position);
684+
} else {
685+
return combined_path.points.size() - 1;
686+
}
687+
});
680688
// remove the point behind of collision check end pose
681-
if (collision_check_end_idx + 1 < combined_path.points.size()) {
682-
combined_path.points.erase(
683-
combined_path.points.begin() + collision_check_end_idx + 1, combined_path.points.end());
684-
}
685-
689+
combined_path.points.erase(
690+
combined_path.points.begin() + collision_check_end_idx + 1, combined_path.points.end());
686691
return combined_path;
687692
}
688693

@@ -949,7 +954,7 @@ std::vector<Pose> StartPlannerModule::searchPullOutStartPoseCandidates(
949954

950955
if (utils::checkCollisionBetweenFootprintAndObjects(
951956
local_vehicle_footprint, *backed_pose, stop_objects_in_pull_out_lanes,
952-
parameters_->collision_check_margin)) {
957+
parameters_->collision_check_margins.back())) {
953958
break; // poses behind this has a collision, so break.
954959
}
955960

0 commit comments

Comments
 (0)