Skip to content

Commit 74d106e

Browse files
feat(start_planner): disable safety check against dynamic objects when ego polygon overlap with centerline (#6236)
* disable safety check against dynamic objects when ego polygon overlap with centerline Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> --------- Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent 18a599e commit 74d106e

File tree

2 files changed

+39
-5
lines changed

2 files changed

+39
-5
lines changed

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -164,6 +164,7 @@ class StartPlannerModule : public SceneModuleInterface
164164

165165
bool isModuleRunning() const;
166166
bool isCurrentPoseOnMiddleOfTheRoad() const;
167+
bool isOverlapWithCenterLane() const;
167168
bool isCloseToOriginalStartPose() const;
168169
bool hasArrivedAtGoal() const;
169170
bool isMoving() const;

planning/behavior_path_start_planner_module/src/start_planner_module.cpp

+38-5
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include "behavior_path_start_planner_module/util.hpp"
2222
#include "motion_utils/trajectory/trajectory.hpp"
2323

24+
#include <lanelet2_extension/utility/message_conversion.hpp>
2425
#include <lanelet2_extension/utility/query.hpp>
2526
#include <lanelet2_extension/utility/utilities.hpp>
2627
#include <magic_enum.hpp>
@@ -211,7 +212,8 @@ bool StartPlannerModule::receivedNewRoute() const
211212

212213
bool StartPlannerModule::requiresDynamicObjectsCollisionDetection() const
213214
{
214-
return parameters_->safety_check_params.enable_safety_check && status_.driving_forward;
215+
return parameters_->safety_check_params.enable_safety_check && status_.driving_forward &&
216+
!isOverlapWithCenterLane();
215217
}
216218

217219
bool StartPlannerModule::noMovingObjectsAround() const
@@ -278,6 +280,37 @@ bool StartPlannerModule::isCurrentPoseOnMiddleOfTheRoad() const
278280
return std::abs(lateral_distance_to_center_lane) < parameters_->th_distance_to_middle_of_the_road;
279281
}
280282

283+
bool StartPlannerModule::isOverlapWithCenterLane() const
284+
{
285+
const Pose & current_pose = planner_data_->self_odometry->pose.pose;
286+
const auto current_lanes = utils::getCurrentLanes(planner_data_);
287+
const auto local_vehicle_footprint = vehicle_info_.createFootprint();
288+
const auto vehicle_footprint =
289+
transformVector(local_vehicle_footprint, tier4_autoware_utils::pose2transform(current_pose));
290+
for (const auto & current_lane : current_lanes) {
291+
std::vector<geometry_msgs::msg::Point> centerline_points;
292+
for (const auto & point : current_lane.centerline()) {
293+
geometry_msgs::msg::Point center_point = lanelet::utils::conversion::toGeomMsgPt(point);
294+
centerline_points.push_back(center_point);
295+
}
296+
297+
for (size_t i = 0; i < centerline_points.size() - 1; ++i) {
298+
const auto & p1 = centerline_points.at(i);
299+
const auto & p2 = centerline_points.at(i + 1);
300+
for (size_t j = 0; j < vehicle_footprint.size() - 1; ++j) {
301+
const auto p3 = tier4_autoware_utils::toMsg(vehicle_footprint[j].to_3d());
302+
const auto p4 = tier4_autoware_utils::toMsg(vehicle_footprint[j + 1].to_3d());
303+
const auto intersection = tier4_autoware_utils::intersect(p1, p2, p3, p4);
304+
305+
if (intersection.has_value()) {
306+
return true;
307+
}
308+
}
309+
}
310+
}
311+
return false;
312+
}
313+
281314
bool StartPlannerModule::isCloseToOriginalStartPose() const
282315
{
283316
const Pose start_pose = planner_data_->route_handler->getOriginalStartPose();
@@ -935,8 +968,8 @@ std::vector<Pose> StartPlannerModule::searchPullOutStartPoseCandidates(
935968
pull_out_lanes, start_pose.position, parameters_->th_moving_object_velocity, 0,
936969
std::numeric_limits<double>::max());
937970

938-
// Set the maximum backward distance less than the distance from the vehicle's base_link to the
939-
// lane's rearmost point to prevent lane departure.
971+
// Set the maximum backward distance less than the distance from the vehicle's base_link to
972+
// the lane's rearmost point to prevent lane departure.
940973
const double current_arc_length =
941974
lanelet::utils::getArcCoordinates(pull_out_lanes, start_pose).length;
942975
const double allowed_backward_distance = std::clamp(
@@ -1224,8 +1257,8 @@ bool StartPlannerModule::isGoalBehindOfEgoInSameRouteSegment() const
12241257
{
12251258
const auto & rh = planner_data_->route_handler;
12261259

1227-
// Check if the goal and ego are in the same route segment. If not, this is out of scope of this
1228-
// function. Return false.
1260+
// Check if the goal and ego are in the same route segment. If not, this is out of scope of
1261+
// this function. Return false.
12291262
lanelet::ConstLanelet ego_lanelet;
12301263
rh->getClosestLaneletWithinRoute(getEgoPose(), &ego_lanelet);
12311264
const auto is_ego_in_goal_route_section = rh->isInGoalRouteSection(ego_lanelet);

0 commit comments

Comments
 (0)