Skip to content

Commit

Permalink
fix(route_handler): exception in route_handler caused by int overflow (
Browse files Browse the repository at this point in the history
…#6755)

Remove cast to int which might cause overflow

Signed-off-by: Sebastian Zęderowski <[email protected]>
Co-authored-by: Sebastian Zęderowski <[email protected]>
  • Loading branch information
sebekx and Sebastian Zęderowski authored Apr 6, 2024
1 parent 1eef4c0 commit 35642a6
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion planning/route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<int>(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);
Expand Down

0 comments on commit 35642a6

Please sign in to comment.