Skip to content

Commit 70f341e

Browse files
committedMay 31, 2024
fix(avoidance): check prev/next lane
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent badf1f7 commit 70f341e

File tree

1 file changed

+29
-5
lines changed
  • planning/autoware_behavior_path_static_obstacle_avoidance_module/src

1 file changed

+29
-5
lines changed
 

‎planning/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp

+29-5
Original file line numberDiff line numberDiff line change
@@ -331,12 +331,36 @@ bool isWithinIntersection(
331331
object_polygon, utils::toPolygon2d(lanelet::utils::to2D(polygon.basicPolygon())));
332332
}
333333

334-
bool isOnEgoLane(const ObjectData & object)
334+
bool isOnEgoLane(const ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler)
335335
{
336336
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());
337+
if (boost::geometry::within(
338+
lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(),
339+
object.overhang_lanelet.polygon2d().basicPolygon())) {
340+
return true;
341+
}
342+
343+
// push previous lanelet
344+
lanelet::ConstLanelets prev_lanelet;
345+
if (route_handler->getPreviousLaneletsWithinRoute(object.overhang_lanelet, &prev_lanelet)) {
346+
if (boost::geometry::within(
347+
lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(),
348+
prev_lanelet.front().polygon2d().basicPolygon())) {
349+
return true;
350+
}
351+
}
352+
353+
// push next lanelet
354+
lanelet::ConstLanelet next_lanelet;
355+
if (route_handler->getNextLaneletWithinRoute(object.overhang_lanelet, &next_lanelet)) {
356+
if (boost::geometry::within(
357+
lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(),
358+
next_lanelet.polygon2d().basicPolygon())) {
359+
return true;
360+
}
361+
}
362+
363+
return false;
340364
}
341365

342366
bool isParallelToEgoLane(const ObjectData & object, const double threshold)
@@ -754,7 +778,7 @@ bool isSatisfiedWithVehicleCondition(
754778
const std::shared_ptr<AvoidanceParameters> & parameters)
755779
{
756780
object.behavior = getObjectBehavior(object, parameters);
757-
object.is_on_ego_lane = isOnEgoLane(object);
781+
object.is_on_ego_lane = isOnEgoLane(object, planner_data->route_handler);
758782

759783
if (isNeverAvoidanceTarget(object, data, planner_data, parameters)) {
760784
return false;

0 commit comments

Comments
 (0)
Please sign in to comment.