From b20553d4a012645b5b750c1c88a14aa69ff28541 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 27 Nov 2024 01:04:08 +0900 Subject: [PATCH] chore: fix build error --- ...t_distance_in_lane_coordinate_distance.cpp | 11 +++++----- .../simulator_core.hpp | 21 ++++++++++++------- 2 files changed, 19 insertions(+), 13 deletions(-) diff --git a/mock/cpp_mock_scenarios/src/measurement/get_distance_in_lane_coordinate_distance.cpp b/mock/cpp_mock_scenarios/src/measurement/get_distance_in_lane_coordinate_distance.cpp index 9b6c59895ee..eed467535ce 100644 --- a/mock/cpp_mock_scenarios/src/measurement/get_distance_in_lane_coordinate_distance.cpp +++ b/mock/cpp_mock_scenarios/src/measurement/get_distance_in_lane_coordinate_distance.cpp @@ -50,7 +50,8 @@ class GetDistanceInLaneCoordinateScenario : public cpp_mock_scenarios::CppScenar to_entity && to_entity->laneMatchingSucceed()) { return traffic_simulator::distance::lateralDistance( from_entity->getCanonicalizedLaneletPose().value(), - to_entity->getCanonicalizedLaneletPose().value(), false, api_.getHdmapUtils()); + to_entity->getCanonicalizedLaneletPose().value(), + traffic_simulator::RoutingConfiguration(), api_.getHdmapUtils()); } } return std::nullopt; @@ -66,8 +67,8 @@ class GetDistanceInLaneCoordinateScenario : public cpp_mock_scenarios::CppScenar auto to_entity_lanelet_pose = to_entity->getCanonicalizedLaneletPose(matching_distance); if (from_entity_lanelet_pose && to_entity_lanelet_pose) { return traffic_simulator::distance::lateralDistance( - from_entity_lanelet_pose.value(), to_entity_lanelet_pose.value(), false, - api_.getHdmapUtils()); + from_entity_lanelet_pose.value(), to_entity_lanelet_pose.value(), + traffic_simulator::RoutingConfiguration(), api_.getHdmapUtils()); } } } @@ -84,8 +85,8 @@ class GetDistanceInLaneCoordinateScenario : public cpp_mock_scenarios::CppScenar to_entity && to_entity->laneMatchingSucceed()) { return traffic_simulator::distance::longitudinalDistance( from_entity->getCanonicalizedLaneletPose().value(), - to_entity->getCanonicalizedLaneletPose().value(), false, true, false, - api_.getHdmapUtils()); + to_entity->getCanonicalizedLaneletPose().value(), false, true, + traffic_simulator::RoutingConfiguration(), api_.getHdmapUtils()); } } return std::nullopt; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index 393b4a11420..1891391ca86 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -176,9 +176,11 @@ class SimulatorCore const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined) -> traffic_simulator::LaneletPose { - const bool allow_lane_change = (routing_algorithm == RoutingAlgorithm::value_type::shortest); + traffic_simulator::RoutingConfiguration routing_configuration; + routing_configuration.allow_lane_change = + (routing_algorithm == RoutingAlgorithm::value_type::shortest); return traffic_simulator::pose::relativeLaneletPose( - from_lanelet_pose, to_lanelet_pose, allow_lane_change, core->getHdmapUtils()); + from_lanelet_pose, to_lanelet_pose, routing_configuration, core->getHdmapUtils()); } static auto makeNativeBoundingBoxRelativeLanePosition( @@ -221,10 +223,12 @@ class SimulatorCore const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined) -> traffic_simulator::LaneletPose { - const bool allow_lane_change = (routing_algorithm == RoutingAlgorithm::value_type::shortest); + traffic_simulator::RoutingConfiguration routing_configuration; + routing_configuration.allow_lane_change = + (routing_algorithm == RoutingAlgorithm::value_type::shortest); return traffic_simulator::pose::boundingBoxRelativeLaneletPose( - from_lanelet_pose, from_bounding_box, to_lanelet_pose, to_bounding_box, allow_lane_change, - core->getHdmapUtils()); + from_lanelet_pose, from_bounding_box, to_lanelet_pose, to_bounding_box, + routing_configuration, core->getHdmapUtils()); } static auto makeNativeBoundingBoxRelativeWorldPosition( @@ -261,14 +265,15 @@ class SimulatorCore const std::string & from_entity_name, const std::string & to_entity_name, const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined) -> int { + traffic_simulator::RoutingConfiguration routing_configuration; + routing_configuration.allow_lane_change = + (routing_algorithm == RoutingAlgorithm::value_type::shortest); if (const auto from_entity = core->getEntity(from_entity_name)) { if (const auto to_entity = core->getEntity(to_entity_name)) { - const bool allow_lane_change = - (routing_algorithm == RoutingAlgorithm::value_type::shortest); if ( auto lane_changes = traffic_simulator::distance::countLaneChanges( from_entity->getCanonicalizedLaneletPose().value(), - to_entity->getCanonicalizedLaneletPose().value(), allow_lane_change, + to_entity->getCanonicalizedLaneletPose().value(), routing_configuration, core->getHdmapUtils())) { return lane_changes.value().first - lane_changes.value().second; }