Skip to content

Commit

Permalink
chore: fix build error
Browse files Browse the repository at this point in the history
  • Loading branch information
HansRobo committed Nov 26, 2024
1 parent a414a7c commit b20553d
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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());
}
}
}
Expand All @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down Expand Up @@ -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(
Expand Down Expand Up @@ -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;
}
Expand Down

0 comments on commit b20553d

Please sign in to comment.