Skip to content

Commit 822d5b5

Browse files
authored
refactor(behavior_velocity_intersection): apply clang-tidy check (#7552)
intersection Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 5974015 commit 822d5b5

File tree

3 files changed

+15
-11
lines changed
  • planning/behavior_velocity_planner

3 files changed

+15
-11
lines changed

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -265,7 +265,9 @@ void IntersectionModule::updateObjectInfoManagerCollision(
265265
continue;
266266
}
267267
const auto & object_passage_interval = object_passage_interval_opt.value();
268-
const auto [object_enter_time, object_exit_time] = object_passage_interval.interval_time;
268+
const auto object_enter_exit_time = object_passage_interval.interval_time;
269+
const auto object_enter_time = std::get<0>(object_enter_exit_time);
270+
const auto object_exit_time = std::get<1>(object_enter_exit_time);
269271
const auto ego_start_itr = std::lower_bound(
270272
time_distance_array.begin(), time_distance_array.end(),
271273
object_enter_time - collision_start_margin_time,

planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp

+1-10
Original file line numberDiff line numberDiff line change
@@ -228,17 +228,8 @@ std::set<lanelet::Id> getAssociativeIntersectionLanelets(
228228
lanelet::ConstLanelet lane, const lanelet::LaneletMapPtr lanelet_map,
229229
const lanelet::routing::RoutingGraphPtr routing_graph);
230230

231-
template <template <class> class Container>
232231
lanelet::ConstLanelets getConstLaneletsFromIds(
233-
lanelet::LaneletMapConstPtr map, const Container<lanelet::Id> & ids)
234-
{
235-
lanelet::ConstLanelets ret{};
236-
for (const auto & id : ids) {
237-
const auto ll = map->laneletLayer.get(id);
238-
ret.push_back(ll);
239-
}
240-
return ret;
241-
}
232+
lanelet::LaneletMapConstPtr map, const std::set<lanelet::Id> & ids);
242233

243234
} // namespace planning_utils
244235
} // namespace autoware::behavior_velocity_planner

planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp

+11
Original file line numberDiff line numberDiff line change
@@ -701,5 +701,16 @@ std::set<lanelet::Id> getAssociativeIntersectionLanelets(
701701
return associative_intersection_lanelets;
702702
}
703703

704+
lanelet::ConstLanelets getConstLaneletsFromIds(
705+
lanelet::LaneletMapConstPtr map, const std::set<lanelet::Id> & ids)
706+
{
707+
lanelet::ConstLanelets ret{};
708+
for (const auto & id : ids) {
709+
const auto ll = map->laneletLayer.get(id);
710+
ret.push_back(ll);
711+
}
712+
return ret;
713+
}
714+
704715
} // namespace planning_utils
705716
} // namespace autoware::behavior_velocity_planner

0 commit comments

Comments
 (0)