diff --git a/simulation/traffic_simulator/include/traffic_simulator/data_type/entity_status.hpp b/simulation/traffic_simulator/include/traffic_simulator/data_type/entity_status.hpp index f253448aad5..19047c1a4e8 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/data_type/entity_status.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/data_type/entity_status.hpp @@ -69,7 +69,7 @@ class CanonicalizedEntityStatus auto laneMatchingSucceed() const noexcept -> bool; auto getLaneletId() const -> lanelet::Id; - auto getLaneletIds() const noexcept -> lanelet::Ids; + auto getLaneletIds() const -> lanelet::Ids; auto getLaneletPose() const -> const LaneletPose &; auto getCanonicalizedLaneletPose() const noexcept -> const std::optional &; diff --git a/simulation/traffic_simulator/src/data_type/entity_status.cpp b/simulation/traffic_simulator/src/data_type/entity_status.cpp index a62befb5e75..53be5df443b 100644 --- a/simulation/traffic_simulator/src/data_type/entity_status.cpp +++ b/simulation/traffic_simulator/src/data_type/entity_status.cpp @@ -141,7 +141,7 @@ auto CanonicalizedEntityStatus::getLaneletId() const -> lanelet::Id return getLaneletPose().lanelet_id; } -auto CanonicalizedEntityStatus::getLaneletIds() const noexcept -> lanelet::Ids +auto CanonicalizedEntityStatus::getLaneletIds() const -> lanelet::Ids { return laneMatchingSucceed() ? lanelet::Ids{getLaneletId()} : lanelet::Ids{}; }