diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 309f2ee3e0b97..4e2f973c7fa67 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -923,7 +923,7 @@ std::vector NormalLaneChange::filterObjectsInTargetLane if (target_polygon) { for (auto & obj : objects.target_lane) { const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj.initial_pose.pose, obj.shape); - if (target_polygon && boost::geometry::intersects(target_polygon.value(), obj_polygon)) { + if (boost::geometry::intersects(target_polygon.value(), obj_polygon)) { filtered_objects.push_back(obj); } }