Skip to content

Commit

Permalink
refactor(behavior_velocity_intersection): apply clang-tidy check (aut…
Browse files Browse the repository at this point in the history
…owarefoundation#7552)

intersection

Signed-off-by: Mamoru Sobue <[email protected]>
Signed-off-by: Simon Eisenmann <[email protected]>
  • Loading branch information
soblin authored and simon-eisenmann-driveblocks committed Jun 26, 2024
1 parent 933ccdd commit 43be343
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,9 @@ void IntersectionModule::updateObjectInfoManagerCollision(
continue;
}
const auto & object_passage_interval = object_passage_interval_opt.value();
const auto [object_enter_time, object_exit_time] = object_passage_interval.interval_time;
const auto object_enter_exit_time = object_passage_interval.interval_time;
const auto object_enter_time = std::get<0>(object_enter_exit_time);
const auto object_exit_time = std::get<1>(object_enter_exit_time);
const auto ego_start_itr = std::lower_bound(
time_distance_array.begin(), time_distance_array.end(),
object_enter_time - collision_start_margin_time,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -228,17 +228,8 @@ std::set<lanelet::Id> getAssociativeIntersectionLanelets(
lanelet::ConstLanelet lane, const lanelet::LaneletMapPtr lanelet_map,
const lanelet::routing::RoutingGraphPtr routing_graph);

template <template <class> class Container>
lanelet::ConstLanelets getConstLaneletsFromIds(
lanelet::LaneletMapConstPtr map, const Container<lanelet::Id> & ids)
{
lanelet::ConstLanelets ret{};
for (const auto & id : ids) {
const auto ll = map->laneletLayer.get(id);
ret.push_back(ll);
}
return ret;
}
lanelet::LaneletMapConstPtr map, const std::set<lanelet::Id> & ids);

} // namespace planning_utils
} // namespace autoware::behavior_velocity_planner
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -701,5 +701,16 @@ std::set<lanelet::Id> getAssociativeIntersectionLanelets(
return associative_intersection_lanelets;
}

lanelet::ConstLanelets getConstLaneletsFromIds(
lanelet::LaneletMapConstPtr map, const std::set<lanelet::Id> & ids)
{
lanelet::ConstLanelets ret{};
for (const auto & id : ids) {
const auto ll = map->laneletLayer.get(id);
ret.push_back(ll);
}
return ret;
}

} // namespace planning_utils
} // namespace autoware::behavior_velocity_planner

0 comments on commit 43be343

Please sign in to comment.