Skip to content

Commit 50641ce

Browse files
authored
Merge pull request #1127 from tier4/hotfix/v0.44.0/avoidance
fix(avoidance): don't use polygon centroid in shiftable ratio calculation (autowarefoundation#6285)
2 parents c906189 + 24bc357 commit 50641ce

File tree

1 file changed

+20
-16
lines changed
  • planning/behavior_path_avoidance_module/src

1 file changed

+20
-16
lines changed

planning/behavior_path_avoidance_module/src/utils.cpp

+20-16
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include "behavior_path_planner_common/utils/traffic_light_utils.hpp"
2222
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
2323

24+
#include <lanelet2_extension/utility/message_conversion.hpp>
2425
#include <tier4_autoware_utils/geometry/geometry.hpp>
2526
#include <tier4_autoware_utils/ros/uuid_helper.hpp>
2627

@@ -476,11 +477,11 @@ bool isObjectOnRoadShoulder(
476477
ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler,
477478
const std::shared_ptr<AvoidanceParameters> & parameters)
478479
{
479-
using boost::geometry::return_centroid;
480480
using boost::geometry::within;
481481
using lanelet::geometry::distance2d;
482482
using lanelet::geometry::toArcCoordinates;
483483
using lanelet::utils::to2D;
484+
using lanelet::utils::conversion::toLaneletPoint;
484485

485486
// assume that there are no parked vehicles in intersection.
486487
std::string turn_direction = object.overhang_lanelet.attributeOr("turn_direction", "else");
@@ -498,13 +499,9 @@ bool isObjectOnRoadShoulder(
498499
// +: object position
499500
// o: nearest point on centerline
500501

501-
lanelet::BasicPoint2d object_centroid(object.centroid.x(), object.centroid.y());
502-
503502
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
504-
const auto centerline_pose =
505-
lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position);
506-
lanelet::BasicPoint3d centerline_point(
507-
centerline_pose.position.x, centerline_pose.position.y, centerline_pose.position.z);
503+
const auto centerline_pos =
504+
lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position).position;
508505

509506
bool is_left_side_parked_vehicle = false;
510507
if (!isOnRight(object)) {
@@ -526,8 +523,9 @@ bool isObjectOnRoadShoulder(
526523
}
527524
}
528525

529-
const auto center_to_left_boundary =
530-
distance2d(to2D(most_left_lanelet.leftBound().basicLineString()), to2D(centerline_point));
526+
const auto center_to_left_boundary = distance2d(
527+
to2D(most_left_lanelet.leftBound().basicLineString()),
528+
to2D(toLaneletPoint(centerline_pos)).basicPoint());
531529

532530
return std::make_pair(
533531
center_to_left_boundary - 0.5 * object.object.shape.dimensions.y, sub_type);
@@ -538,7 +536,8 @@ bool isObjectOnRoadShoulder(
538536
}
539537

540538
const auto arc_coordinates = toArcCoordinates(
541-
to2D(object.overhang_lanelet.centerline().basicLineString()), object_centroid);
539+
to2D(object.overhang_lanelet.centerline().basicLineString()),
540+
to2D(toLaneletPoint(object_pose.position)).basicPoint());
542541
object.shiftable_ratio = arc_coordinates.distance / object_shiftable_distance;
543542

544543
is_left_side_parked_vehicle = object.shiftable_ratio > parameters->object_check_shiftable_ratio;
@@ -564,8 +563,9 @@ bool isObjectOnRoadShoulder(
564563
}
565564
}
566565

567-
const auto center_to_right_boundary =
568-
distance2d(to2D(most_right_lanelet.rightBound().basicLineString()), to2D(centerline_point));
566+
const auto center_to_right_boundary = distance2d(
567+
to2D(most_right_lanelet.rightBound().basicLineString()),
568+
to2D(toLaneletPoint(centerline_pos)).basicPoint());
569569

570570
return std::make_pair(
571571
center_to_right_boundary - 0.5 * object.object.shape.dimensions.y, sub_type);
@@ -576,7 +576,8 @@ bool isObjectOnRoadShoulder(
576576
}
577577

578578
const auto arc_coordinates = toArcCoordinates(
579-
to2D(object.overhang_lanelet.centerline().basicLineString()), object_centroid);
579+
to2D(object.overhang_lanelet.centerline().basicLineString()),
580+
to2D(toLaneletPoint(object_pose.position)).basicPoint());
580581
object.shiftable_ratio = -1.0 * arc_coordinates.distance / object_shiftable_distance;
581582

582583
is_right_side_parked_vehicle =
@@ -754,6 +755,8 @@ bool isSatisfiedWithVehicleCondition(
754755
const std::shared_ptr<AvoidanceParameters> & parameters)
755756
{
756757
using boost::geometry::within;
758+
using lanelet::utils::to2D;
759+
using lanelet::utils::conversion::toLaneletPoint;
757760

758761
object.behavior = getObjectBehavior(object, parameters);
759762
object.is_within_intersection = isWithinIntersection(object, planner_data->route_handler);
@@ -764,9 +767,10 @@ bool isSatisfiedWithVehicleCondition(
764767
}
765768

766769
// check vehicle shift ratio
767-
lanelet::BasicPoint2d object_centroid(object.centroid.x(), object.centroid.y());
768-
const auto on_ego_driving_lane =
769-
within(object_centroid, object.overhang_lanelet.polygon2d().basicPolygon());
770+
const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position;
771+
const auto on_ego_driving_lane = within(
772+
to2D(toLaneletPoint(object_pos)).basicPoint(),
773+
object.overhang_lanelet.polygon2d().basicPolygon());
770774
if (on_ego_driving_lane) {
771775
if (isObjectOnRoadShoulder(object, planner_data->route_handler, parameters)) {
772776
return true;

0 commit comments

Comments
 (0)