Skip to content

Commit

Permalink
fix(traffic_simulator): adapt lanelet-wapper::pose to changes in hdma…
Browse files Browse the repository at this point in the history
…p_utils
  • Loading branch information
dmoszynski committed Dec 10, 2024
1 parent af6198c commit bd67439
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -81,12 +81,12 @@ auto matchToLane(
-> std::optional<lanelet::Id>;

auto leftLaneletIds(
const lanelet::Id lanelet_id, const RoutingGraphType type,
const bool include_opposite_direction = true) -> lanelet::Ids;
const lanelet::Id lanelet_id, const RoutingGraphType type, const bool include_opposite_direction)
-> lanelet::Ids;

auto rightLaneletIds(
const lanelet::Id lanelet_id, const RoutingGraphType type,
const bool include_opposite_direction = true) -> lanelet::Ids;
const lanelet::Id lanelet_id, const RoutingGraphType type, const bool include_opposite_direction)
-> lanelet::Ids;
} // namespace pose
} // namespace lanelet_wrapper
} // namespace traffic_simulator
Expand Down
15 changes: 9 additions & 6 deletions simulation/traffic_simulator/src/lanelet_wrapper/pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -425,10 +425,11 @@ auto leftLaneletIds(
-> lanelet::Ids
{
if (include_opposite_direction) {
return lanelet_map::laneletIds(LaneletWrapper::routingGraph(type)->lefts(
LaneletWrapper::map()->laneletLayer.get(lanelet_id)));
throw common::Error(
"lanelet_wrapper::pose::leftLaneletIds with include_opposite_direction=true is not "
"implemented yet.");
} else {
return lanelet_map::laneletIds(LaneletWrapper::routingGraph(type)->adjacentLefts(
return lanelet_map::laneletIds(LaneletWrapper::routingGraph(type)->lefts(
LaneletWrapper::map()->laneletLayer.get(lanelet_id)));
}
}
Expand All @@ -438,10 +439,12 @@ auto rightLaneletIds(
-> lanelet::Ids
{
if (include_opposite_direction) {
return lanelet_map::laneletIds(LaneletWrapper::routingGraph(type)->rights(
LaneletWrapper::map()->laneletLayer.get(lanelet_id)));
throw common::Error(
"lanelet_wrapper::pose::rightLaneletIds with include_opposite_direction=true is not "
"implemented "
"yet.");
} else {
return lanelet_map::laneletIds(LaneletWrapper::routingGraph(type)->adjacentRights(
return lanelet_map::laneletIds(LaneletWrapper::routingGraph(type)->rights(
LaneletWrapper::map()->laneletLayer.get(lanelet_id)));
}
}
Expand Down

0 comments on commit bd67439

Please sign in to comment.