From 35642a6df0a12750256f459b40546e90bcd5c09e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Sebastian=20Z=C4=99derowski?= Date: Sat, 6 Apr 2024 06:55:14 +0200 Subject: [PATCH] fix(route_handler): exception in route_handler caused by int overflow (#6755) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Remove cast to int which might cause overflow Signed-off-by: Sebastian Zęderowski Co-authored-by: Sebastian Zęderowski --- planning/route_handler/src/route_handler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 8cec5073efb6a..8d143fcf0b87d 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -1708,7 +1708,7 @@ PathWithLaneId RouteHandler::getCenterLinePath( // append a point only when having one point so that yaw calculation would work if (reference_path.points.size() == 1) { - const lanelet::Id lane_id = static_cast(reference_path.points.front().lane_ids.front()); + const lanelet::Id lane_id = reference_path.points.front().lane_ids.front(); const auto lanelet = lanelet_map_ptr_->laneletLayer.get(lane_id); const auto point = reference_path.points.front().point.pose.position; const auto lane_yaw = lanelet::utils::getLaneletAngle(lanelet, point);