Skip to content

Commit 9b736d5

Browse files
feat(start_planner): keep distance against front objects (#5983)
* refactor extractCollisionCheckPath Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> --------- Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> Co-authored-by: Kosuke Takeuchi <kosuke.tnp@gmail.com>
1 parent 49d5f22 commit 9b736d5

File tree

6 files changed

+18
-6
lines changed

6 files changed

+18
-6
lines changed

planning/behavior_path_start_planner_module/README.md

+2-1
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,8 @@ PullOutPath --o PullOutPlannerBase
7575
| intersection_search_length | [m] | double | check if intersections exist within this length | 30.0 |
7676
| length_ratio_for_turn_signal_deactivation_near_intersection | [m] | double | deactivate turn signal of this module near intersection | 0.5 |
7777
| collision_check_margin | [m] | double | Obstacle collision check margin | 1.0 |
78-
| collision_check_distance_from_end | [m] | double | collision check distance from end point. currently only for pull out | 15.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 |
7980
| center_line_path_interval | [m] | double | reference center line path point interval | 1.0 |
8081

8182
## Safety check with static obstacles

planning/behavior_path_start_planner_module/config/start_planner.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
th_stopped_time: 1.0
88
collision_check_margin: 1.0
99
collision_check_distance_from_end: 1.0
10+
collision_check_margin_from_front_object: 5.0
1011
th_moving_object_velocity: 1.0
1112
th_distance_to_middle_of_the_road: 0.5
1213
center_line_path_interval: 1.0

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -174,7 +174,7 @@ class StartPlannerModule : public SceneModuleInterface
174174
const Pose & start_pose_candidate, const std::shared_ptr<PullOutPlannerBase> & planner,
175175
const Pose & refined_start_pose, const Pose & goal_pose);
176176

177-
PathWithLaneId extractCollisionCheckPath(const PullOutPath & path);
177+
PathWithLaneId extractCollisionCheckSection(const PullOutPath & path);
178178
void updateStatusWithCurrentPath(
179179
const behavior_path_planner::PullOutPath & path, const Pose & start_pose,
180180
const behavior_path_planner::PlannerType & planner_type);

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@ struct StartPlannerParameters
4444
double length_ratio_for_turn_signal_deactivation_near_intersection{0.0};
4545
double collision_check_margin{0.0};
4646
double collision_check_distance_from_end{0.0};
47+
double collision_check_margin_from_front_object{0.0};
4748
double th_moving_object_velocity{0.0};
4849
double center_line_path_interval{0.0};
4950

planning/behavior_path_start_planner_module/src/manager.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,8 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
4646
p.collision_check_margin = node->declare_parameter<double>(ns + "collision_check_margin");
4747
p.collision_check_distance_from_end =
4848
node->declare_parameter<double>(ns + "collision_check_distance_from_end");
49+
p.collision_check_margin_from_front_object =
50+
node->declare_parameter<double>(ns + "collision_check_margin_from_front_object");
4951
p.th_moving_object_velocity = node->declare_parameter<double>(ns + "th_moving_object_velocity");
5052
p.center_line_path_interval = node->declare_parameter<double>(ns + "center_line_path_interval");
5153
// shift pull out

planning/behavior_path_start_planner_module/src/start_planner_module.cpp

+11-4
Original file line numberDiff line numberDiff line change
@@ -645,7 +645,7 @@ bool StartPlannerModule::findPullOutPath(
645645

646646
// check collision
647647
if (utils::checkCollisionBetweenPathFootprintsAndObjects(
648-
vehicle_footprint, extractCollisionCheckPath(*pull_out_path), pull_out_lane_stop_objects,
648+
vehicle_footprint, extractCollisionCheckSection(*pull_out_path), pull_out_lane_stop_objects,
649649
parameters_->collision_check_margin)) {
650650
return false;
651651
}
@@ -660,7 +660,7 @@ bool StartPlannerModule::findPullOutPath(
660660
return true;
661661
}
662662

663-
PathWithLaneId StartPlannerModule::extractCollisionCheckPath(const PullOutPath & path)
663+
PathWithLaneId StartPlannerModule::extractCollisionCheckSection(const PullOutPath & path)
664664
{
665665
PathWithLaneId combined_path;
666666
for (const auto & partial_path : path.partial_paths) {
@@ -912,6 +912,10 @@ std::vector<Pose> StartPlannerModule::searchPullOutStartPoseCandidates(
912912
pull_out_lanes, start_pose.position, parameters_->th_moving_object_velocity,
913913
backward_path_length, std::numeric_limits<double>::max());
914914

915+
const auto front_stop_objects_in_pull_out_lanes = filterStopObjectsInPullOutLanes(
916+
pull_out_lanes, start_pose.position, parameters_->th_moving_object_velocity, 0,
917+
std::numeric_limits<double>::max());
918+
915919
// Set the maximum backward distance less than the distance from the vehicle's base_link to the
916920
// lane's rearmost point to prevent lane departure.
917921
const double current_arc_length =
@@ -924,9 +928,12 @@ std::vector<Pose> StartPlannerModule::searchPullOutStartPoseCandidates(
924928
back_distance += parameters_->backward_search_resolution) {
925929
const auto backed_pose = calcLongitudinalOffsetPose(
926930
back_path_from_start_pose.points, start_pose.position, -back_distance);
927-
if (!backed_pose) {
931+
if (!backed_pose) continue;
932+
933+
if (utils::checkCollisionBetweenFootprintAndObjects(
934+
local_vehicle_footprint, *backed_pose, front_stop_objects_in_pull_out_lanes,
935+
parameters_->collision_check_margin_from_front_object))
928936
continue;
929-
}
930937

931938
const double backed_pose_arc_length =
932939
lanelet::utils::getArcCoordinates(pull_out_lanes, *backed_pose).length;

0 commit comments

Comments
 (0)