diff --git a/planning/autoware_route_handler/src/route_handler.cpp b/planning/autoware_route_handler/src/route_handler.cpp index 06dd7db7180da..ec5f7bb5e0080 100644 --- a/planning/autoware_route_handler/src/route_handler.cpp +++ b/planning/autoware_route_handler/src/route_handler.cpp @@ -1926,7 +1926,6 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints( } lanelet::Optional optional_route; - std::vector candidate_paths; lanelet::routing::LaneletPath shortest_path; bool is_route_found = false;