From 9ccee029e8d4101f3bc38b7c6f8b9222733a15f0 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 5 Feb 2024 17:19:09 +0900 Subject: [PATCH] fix(avoidance): don't use polygon centroid in shiftable ratio calculation (#6285) Signed-off-by: satoshi-ota Co-authored-by: Kotaro Yoshimoto --- .../src/utils.cpp | 36 ++++++++++--------- 1 file changed, 20 insertions(+), 16 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index 7309882a94e16..2bc909c115c87 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -21,6 +21,7 @@ #include "behavior_path_planner_common/utils/traffic_light_utils.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" +#include #include #include @@ -484,11 +485,11 @@ bool isObjectOnRoadShoulder( ObjectData & object, const std::shared_ptr & route_handler, const std::shared_ptr & parameters) { - using boost::geometry::return_centroid; using boost::geometry::within; using lanelet::geometry::distance2d; using lanelet::geometry::toArcCoordinates; using lanelet::utils::to2D; + using lanelet::utils::conversion::toLaneletPoint; // assume that there are no parked vehicles in intersection. std::string turn_direction = object.overhang_lanelet.attributeOr("turn_direction", "else"); @@ -506,13 +507,9 @@ bool isObjectOnRoadShoulder( // +: object position // o: nearest point on centerline - lanelet::BasicPoint2d object_centroid(object.centroid.x(), object.centroid.y()); - const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; - const auto centerline_pose = - lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position); - lanelet::BasicPoint3d centerline_point( - centerline_pose.position.x, centerline_pose.position.y, centerline_pose.position.z); + const auto centerline_pos = + lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position).position; bool is_left_side_parked_vehicle = false; if (!isOnRight(object)) { @@ -534,8 +531,9 @@ bool isObjectOnRoadShoulder( } } - const auto center_to_left_boundary = - distance2d(to2D(most_left_lanelet.leftBound().basicLineString()), to2D(centerline_point)); + const auto center_to_left_boundary = distance2d( + to2D(most_left_lanelet.leftBound().basicLineString()), + to2D(toLaneletPoint(centerline_pos)).basicPoint()); return std::make_pair( center_to_left_boundary - 0.5 * object.object.shape.dimensions.y, sub_type); @@ -546,7 +544,8 @@ bool isObjectOnRoadShoulder( } const auto arc_coordinates = toArcCoordinates( - to2D(object.overhang_lanelet.centerline().basicLineString()), object_centroid); + to2D(object.overhang_lanelet.centerline().basicLineString()), + to2D(toLaneletPoint(object_pose.position)).basicPoint()); object.shiftable_ratio = arc_coordinates.distance / object_shiftable_distance; is_left_side_parked_vehicle = object.shiftable_ratio > parameters->object_check_shiftable_ratio; @@ -572,8 +571,9 @@ bool isObjectOnRoadShoulder( } } - const auto center_to_right_boundary = - distance2d(to2D(most_right_lanelet.rightBound().basicLineString()), to2D(centerline_point)); + const auto center_to_right_boundary = distance2d( + to2D(most_right_lanelet.rightBound().basicLineString()), + to2D(toLaneletPoint(centerline_pos)).basicPoint()); return std::make_pair( center_to_right_boundary - 0.5 * object.object.shape.dimensions.y, sub_type); @@ -584,7 +584,8 @@ bool isObjectOnRoadShoulder( } const auto arc_coordinates = toArcCoordinates( - to2D(object.overhang_lanelet.centerline().basicLineString()), object_centroid); + to2D(object.overhang_lanelet.centerline().basicLineString()), + to2D(toLaneletPoint(object_pose.position)).basicPoint()); object.shiftable_ratio = -1.0 * arc_coordinates.distance / object_shiftable_distance; is_right_side_parked_vehicle = @@ -760,6 +761,8 @@ bool isSatisfiedWithVehicleCondition( const std::shared_ptr & parameters) { using boost::geometry::within; + using lanelet::utils::to2D; + using lanelet::utils::conversion::toLaneletPoint; object.behavior = getObjectBehavior(object, parameters); object.is_within_intersection = isWithinIntersection(object, planner_data->route_handler); @@ -770,9 +773,10 @@ bool isSatisfiedWithVehicleCondition( } // check vehicle shift ratio - lanelet::BasicPoint2d object_centroid(object.centroid.x(), object.centroid.y()); - const auto on_ego_driving_lane = - within(object_centroid, object.overhang_lanelet.polygon2d().basicPolygon()); + const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position; + const auto on_ego_driving_lane = within( + to2D(toLaneletPoint(object_pos)).basicPoint(), + object.overhang_lanelet.polygon2d().basicPolygon()); if (on_ego_driving_lane) { if (isObjectOnRoadShoulder(object, planner_data->route_handler, parameters)) { return true;