From a915fcbe6b7ed3b953eb4e0cc41c8b670e6f33cb Mon Sep 17 00:00:00 2001 From: Muhammad Zulfaqar Azmi Date: Tue, 14 Jun 2022 13:48:14 +0900 Subject: [PATCH] fix(route_handler): dereference to null cause avoidance module crash This crash will not appear unless drivable area boundary is added. Signed-off-by: Muhammad Zulfaqar Azmi --- planning/route_handler/src/route_handler.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 91b79e900ca7..718ec34e1fb9 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -938,6 +938,9 @@ lanelet::ConstLanelets RouteHandler::getAllLeftSharedLinestringLanelets( while (lanelet_at_left) { linestring_shared.push_back(lanelet_at_left.get()); lanelet_at_left = getLeftLanelet(lanelet_at_left.get()); + if (!lanelet_at_left) { + break; + } lanelet_at_left_opposite = getLeftOppositeLanelets(lanelet_at_left.get()); } @@ -961,6 +964,9 @@ lanelet::ConstLanelets RouteHandler::getAllRightSharedLinestringLanelets( while (lanelet_at_right) { linestring_shared.push_back(lanelet_at_right.get()); lanelet_at_right = getRightLanelet(lanelet_at_right.get()); + if (!lanelet_at_right) { + break; + } lanelet_at_right_opposite = getRightOppositeLanelets(lanelet_at_right.get()); }