Skip to content

Commit f52fa9a

Browse files
satoshi-otaa-maumau
authored andcommitted
fix(avoidance): fix bugs in parked vehicle filtering logic (autowarefoundation#7072)
* fix(avoidance): check prev/next lane Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(avoidance): fix parked vehicle filtering Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(avoidance): check intersection location Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 3f4b71c commit f52fa9a

File tree

1 file changed

+80
-15
lines changed
  • planning/autoware_behavior_path_static_obstacle_avoidance_module/src

1 file changed

+80
-15
lines changed

planning/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp

+80-15
Original file line numberDiff line numberDiff line change
@@ -318,25 +318,55 @@ bool isWithinCrosswalk(
318318
bool isWithinIntersection(
319319
const ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler)
320320
{
321-
const std::string id = object.overhang_lanelet.attributeOr("intersection_area", "else");
322-
if (id == "else") {
321+
const std::string area_id = object.overhang_lanelet.attributeOr("intersection_area", "else");
322+
if (area_id == "else") {
323+
return false;
324+
}
325+
326+
const std::string location = object.overhang_lanelet.attributeOr("location", "else");
327+
if (location == "private") {
323328
return false;
324329
}
325330

326331
const auto object_polygon = tier4_autoware_utils::toPolygon2d(object.object);
327332

328-
const auto polygon = route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(id.c_str()));
333+
const auto polygon =
334+
route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(area_id.c_str()));
329335

330336
return boost::geometry::within(
331337
object_polygon, utils::toPolygon2d(lanelet::utils::to2D(polygon.basicPolygon())));
332338
}
333339

334-
bool isOnEgoLane(const ObjectData & object)
340+
bool isOnEgoLane(const ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler)
335341
{
336342
const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position;
337-
return boost::geometry::within(
338-
lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(),
339-
object.overhang_lanelet.polygon2d().basicPolygon());
343+
if (boost::geometry::within(
344+
lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(),
345+
object.overhang_lanelet.polygon2d().basicPolygon())) {
346+
return true;
347+
}
348+
349+
// push previous lanelet
350+
lanelet::ConstLanelets prev_lanelet;
351+
if (route_handler->getPreviousLaneletsWithinRoute(object.overhang_lanelet, &prev_lanelet)) {
352+
if (boost::geometry::within(
353+
lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(),
354+
prev_lanelet.front().polygon2d().basicPolygon())) {
355+
return true;
356+
}
357+
}
358+
359+
// push next lanelet
360+
lanelet::ConstLanelet next_lanelet;
361+
if (route_handler->getNextLaneletWithinRoute(object.overhang_lanelet, &next_lanelet)) {
362+
if (boost::geometry::within(
363+
lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(),
364+
next_lanelet.polygon2d().basicPolygon())) {
365+
return true;
366+
}
367+
}
368+
369+
return false;
340370
}
341371

342372
bool isParallelToEgoLane(const ObjectData & object, const double threshold)
@@ -604,14 +634,49 @@ bool isNeverAvoidanceTarget(
604634

605635
if (object.is_on_ego_lane) {
606636
const auto right_lane =
607-
planner_data->route_handler->getRightLanelet(object.overhang_lanelet, true, false);
637+
planner_data->route_handler->getRightLanelet(object.overhang_lanelet, true, true);
638+
if (right_lane.has_value() && isOnRight(object)) {
639+
const lanelet::Attribute & right_lane_sub_type =
640+
right_lane.value().attribute(lanelet::AttributeName::Subtype);
641+
if (right_lane_sub_type != "road_shoulder") {
642+
object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
643+
RCLCPP_DEBUG(
644+
rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it.");
645+
return true;
646+
}
647+
648+
const auto object_polygon = tier4_autoware_utils::toPolygon2d(object.object);
649+
const auto is_disjoint_right_lane =
650+
boost::geometry::disjoint(object_polygon, right_lane.value().polygon2d().basicPolygon());
651+
if (is_disjoint_right_lane) {
652+
object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
653+
RCLCPP_DEBUG(
654+
rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it.");
655+
return true;
656+
}
657+
}
658+
608659
const auto left_lane =
609-
planner_data->route_handler->getLeftLanelet(object.overhang_lanelet, true, false);
610-
if (right_lane.has_value() && left_lane.has_value()) {
611-
object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
612-
RCLCPP_DEBUG(
613-
rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it.");
614-
return true;
660+
planner_data->route_handler->getLeftLanelet(object.overhang_lanelet, true, true);
661+
if (left_lane.has_value() && !isOnRight(object)) {
662+
const lanelet::Attribute & left_lane_sub_type =
663+
left_lane.value().attribute(lanelet::AttributeName::Subtype);
664+
if (left_lane_sub_type != "road_shoulder") {
665+
object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
666+
RCLCPP_DEBUG(
667+
rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it.");
668+
return true;
669+
}
670+
671+
const auto object_polygon = tier4_autoware_utils::toPolygon2d(object.object);
672+
const auto is_disjoint_left_lane =
673+
boost::geometry::disjoint(object_polygon, left_lane.value().polygon2d().basicPolygon());
674+
if (is_disjoint_left_lane) {
675+
object.info = ObjectInfo::IS_NOT_PARKING_OBJECT;
676+
RCLCPP_DEBUG(
677+
rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it.");
678+
return true;
679+
}
615680
}
616681
}
617682

@@ -754,7 +819,7 @@ bool isSatisfiedWithVehicleCondition(
754819
const std::shared_ptr<AvoidanceParameters> & parameters)
755820
{
756821
object.behavior = getObjectBehavior(object, parameters);
757-
object.is_on_ego_lane = isOnEgoLane(object);
822+
object.is_on_ego_lane = isOnEgoLane(object, planner_data->route_handler);
758823

759824
if (isNeverAvoidanceTarget(object, data, planner_data, parameters)) {
760825
return false;

0 commit comments

Comments
 (0)