Commit 822d5b5 1 parent 5974015 commit 822d5b5 Copy full SHA for 822d5b5
File tree 3 files changed +15
-11
lines changed
planning/behavior_velocity_planner
autoware_behavior_velocity_intersection_module/src
autoware_behavior_velocity_planner_common
include/autoware/behavior_velocity_planner_common/utilization
3 files changed +15
-11
lines changed Original file line number Diff line number Diff line change @@ -265,7 +265,9 @@ void IntersectionModule::updateObjectInfoManagerCollision(
265
265
continue ;
266
266
}
267
267
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);
269
271
const auto ego_start_itr = std::lower_bound (
270
272
time_distance_array.begin (), time_distance_array.end (),
271
273
object_enter_time - collision_start_margin_time,
Original file line number Diff line number Diff line change @@ -228,17 +228,8 @@ std::set<lanelet::Id> getAssociativeIntersectionLanelets(
228
228
lanelet::ConstLanelet lane, const lanelet::LaneletMapPtr lanelet_map,
229
229
const lanelet::routing::RoutingGraphPtr routing_graph);
230
230
231
- template <template <class > class Container >
232
231
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);
242
233
243
234
} // namespace planning_utils
244
235
} // namespace autoware::behavior_velocity_planner
Original file line number Diff line number Diff line change @@ -701,5 +701,16 @@ std::set<lanelet::Id> getAssociativeIntersectionLanelets(
701
701
return associative_intersection_lanelets;
702
702
}
703
703
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
+
704
715
} // namespace planning_utils
705
716
} // namespace autoware::behavior_velocity_planner
You can’t perform that action at this time.
0 commit comments