From 2ebc41a90f1eeb5443410c951f8b3f1654a6d54f Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 10 Dec 2024 11:48:44 +0900 Subject: [PATCH] =?UTF-8?q?fix:=E3=80=80disable=20default=20argument=20val?= =?UTF-8?q?ue=20for=20include=5Foppsite=5Fdirection=20in=20=20HdMapUtils::?= =?UTF-8?q?getLeftLaneletIds/getRightLaneletIds?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../include/traffic_simulator/hdmap_utils/hdmap_utils.hpp | 4 ++-- simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp | 5 +++-- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp index b2eac48c625..35247f9f03f 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp @@ -204,7 +204,7 @@ class HdMapUtils auto getLeftLaneletIds( const lanelet::Id, const traffic_simulator::RoutingGraphType, - const bool include_opposite_direction = false) const -> lanelet::Ids; + const bool include_opposite_direction) const -> lanelet::Ids; auto getLongitudinalDistance( const traffic_simulator_msgs::msg::LaneletPose & from_pose, @@ -269,7 +269,7 @@ class HdMapUtils auto getRightLaneletIds( const lanelet::Id, const traffic_simulator::RoutingGraphType, - const bool include_opposite_direction = false) const -> lanelet::Ids; + const bool include_opposite_direction) const -> lanelet::Ids; auto getRightOfWayLaneletIds(const lanelet::Ids &) const -> std::unordered_map; diff --git a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp index ee30b9cc1f4..d711dfc4a62 100644 --- a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp +++ b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp @@ -220,11 +220,12 @@ auto HdMapUtils::countLaneChanges( if (auto followings = getNextLaneletIds(previous, routing_configuration.routing_graph_type); std::find(followings.begin(), followings.end(), current) == followings.end()) { - if (auto lefts = getLeftLaneletIds(previous, routing_configuration.routing_graph_type); + if (auto lefts = + getLeftLaneletIds(previous, routing_configuration.routing_graph_type, false); std::find(lefts.begin(), lefts.end(), current) != lefts.end()) { lane_changes.first++; } else if (auto rights = - getRightLaneletIds(previous, routing_configuration.routing_graph_type); + getRightLaneletIds(previous, routing_configuration.routing_graph_type, false); std::find(rights.begin(), rights.end(), current) != rights.end()) { lane_changes.second++; }