diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 589a98d7d5ab4..5a864568a2873 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -1593,7 +1593,7 @@ double RouteHandler::getTotalLateralDistanceToPreferredLane( const lanelet::ConstLanelet & lanelet, const Direction direction) const { const auto intervals = getLateralIntervalsToPreferredLane(lanelet, direction); - return std::accumulate(intervals.begin(), intervals.end(), 0); + return std::accumulate(intervals.begin(), intervals.end(), 0.0); } std::vector RouteHandler::getLateralIntervalsToPreferredLane(