diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp index 739b1122be6a1..906d39a9b127f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp @@ -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, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp index 591a30928fd09..5f1c17ea1b815 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp @@ -228,17 +228,8 @@ std::set getAssociativeIntersectionLanelets( lanelet::ConstLanelet lane, const lanelet::LaneletMapPtr lanelet_map, const lanelet::routing::RoutingGraphPtr routing_graph); -template