Skip to content

Commit

Permalink
fix(avoidance): use getRightLanelet
Browse files Browse the repository at this point in the history
Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota committed Mar 17, 2024
1 parent 20564be commit fee4a57
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions planning/behavior_path_avoidance_module/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -702,8 +702,8 @@ bool isNeverAvoidanceTarget(

if (object.is_on_ego_lane) {
if (
!!planner_data->route_handler->getRoutingGraphPtr()->right(object.overhang_lanelet) &&
!!planner_data->route_handler->getRoutingGraphPtr()->left(object.overhang_lanelet)) {
planner_data->route_handler->getRightLanelet(object.overhang_lanelet).has_value() &&
planner_data->route_handler->getLeftLanelet(object.overhang_lanelet).has_value()) {
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object isn't on the edge lane. never avoid it.");
return true;
Expand Down

0 comments on commit fee4a57

Please sign in to comment.