Skip to content

RJD-1057 (5/5): Remove non-API member functions: Improve responsibility simulator_core<->api #1337

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Conversation

TauTheLepton
Copy link
Contributor

@TauTheLepton TauTheLepton commented Aug 1, 2024

Description

Abstract

This pull request aims to improve the responsibility division between traffic_simulator API and openscenario_interpreter SimulatorCore.
The changes include refactoring, renaming functions and reordering them in the source files. So even though the number of changes reported by github is rather high, many of the changes consist of moving functions around with slight if none modifications.

Background

This pull request is one of many that aim to modularize the scenario_simulator_v2.

Details

Canonicalization

The main changes are that canonicalization process (of lanelet pose) is a responsibility of traffic_simulator. This way the communication with traffic_simulator API is done on NON canonicalized data structures and traffic_simulator has to canonicalize the data.

Note

A result of aforementioned changes, most of cpp_mock_scenarios had to be adjusted to communicate using regular lanelet pose instead of canonicalized one.
This leads to GitHub reporting many lines changed and the PR seem to be big, but many of these changes are simply adjusting cpp_mock_scenarios like the following.

Before

auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.0, 0.0),
getVehicleParameters());

After
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructLaneletPose(34741, 0.0, 0.0),
getVehicleParameters());

Important

Because of the change of canonicalization, the NativeLanePosition type in SimulatorCore has been changed

Before

using NativeLanePosition = traffic_simulator::CanonicalizedLaneletPose;
using NativeRelativeLanePosition = traffic_simulator::LaneletPose;

After
using NativeLanePosition = traffic_simulator::LaneletPose;
using NativeRelativeLanePosition = NativeLanePosition;

SimulatorCore

This PR focuses on improving the interaction between the API and SimulatorCore.
This is why SimulatorCore needed many modifications.
Below they are broken down into the subclasses of SimulatorCore.

General

Changes include conversion of some SimulatorCore classes member functions to explicitly list arguments instead of using the variadic templates.
For example applyAddEntityAction before change

template <typename... Ts>
static auto applyAddEntityAction(Ts &&... xs) -> decltype(auto)
{
return core->spawn(std::forward<decltype(xs)>(xs)...);
}

and after the change
template <typename PoseType, typename ParamsType>
static auto applyAddEntityAction(
const std::string & entity_name, const PoseType & pose, const ParamsType & parameters,
const std::string & behavior, const std::string & model3d) -> void
{
core->spawn(entity_name, pose, parameters, behavior, model3d);
}

Many member functions of SimulatorCore::ConditionEvaluation have been changed to include a check whether the Entity exists and if not return NaN or other appropriate default value.
For example SimulatorCore::ConditionEvaluation::evaluateCollisionCondition before change

template <typename... Ts>
static auto evaluateCollisionCondition(Ts &&... xs) -> bool
{
return core->checkCollision(std::forward<decltype(xs)>(xs)...);
}

and after the change
static auto evaluateCollisionCondition(
const std::string & first_entity_name, const std::string & second_entity_name) -> bool
{
if (core->isEntityExist(first_entity_name) && core->isEntityExist(second_entity_name)) {
return core->checkCollision(first_entity_name, second_entity_name);
} else {
return false;
}
}

Others

Function NonStandardOperation::activateNonUserDefinedControllers has been moved directly to the SimulatorCore class.

CoordinateSystemConversion

  • SimulatorCore::CoordinateSystemConversion::convert<> functions have been renamed to convertToNativeLanePosition and convertToNativeWorldPosition and slightly improved.
  • 2 out of 3 CoordinateSystemConversion::makeNativeRelativeWorldPosition functions have been removed, as they were no longer needed.
  • Many of the relative pose related functions from SimulatorCore::CoordinateSystemConversion have been refactored and moved to a new class SimulatorCore::DistanceConditionEvaluation as they were only used for distance calculations anyway.

DistanceConditionEvaluation

This subclass has been added to group all distance functions. Many functions added to this class are functions moved from SimulatorCore::CoordinateSystemConversion.

Note

Keep in mind, that due to the fact, that many underlying API functions can be passed some combination of Entity name and position as arguments, many function of this class have been converted to templates to accept different types as arguments.
These functions perform common checks whether an Entity exists (when the name is passed as an argument). These checks have been separated in a prerequisite function.

  • Relative pose functions from CoordinateSystemConversion class have been removed in favor of new distance functions, because the relative pose was only used for distance calculation.
    • CoordinateSystemConversion::makeNativeRelativeLanePosition has been removed in favor of DistanceConditionEvaluation::lateralEntityDistance and DistanceConditionEvaluation::longitudinalEntityDistance
    • CoordinateSystemConversion::makeNativeBoundingBoxRelativeLanePosition has been removed in favor of DistanceConditionEvaluation::lateralEntityBoundingBoxDistance and DistanceConditionEvaluation::longitudinalEntityBoundingBoxDistance
    • CoordinateSystemConversion::makeNativeBoundingBoxRelativeWorldPosition has been removed in favor of DistanceConditionEvaluation::euclideanBoundingBoxDistance
    • DistanceConditionEvaluation::euclideanDistance has been added for distance calculation.
  • CoordinateSystemConversion::evaluateLateralRelativeLanes has been changed to lateralRelativeLanes with some slight modifications.
  • lateralLaneDistance has been developed to be used instead of CoordinateSystemConversion::makeNativeRelativeWorldPosition
  • longitudinalLaneDistance has been developed to be used instead of CoordinateSystemConversion::makeNativeRelativeWorldPosition
  • lateralLaneBoundingBoxDistance has been developed to be used instead of CoordinateSystemConversion::makeNativeBoundingBoxRelativeLanePosition
  • longitudinalLaneBoundingBoxDistance has been developed to be used instead of CoordinateSystemConversion::makeNativeBoundingBoxRelativeLanePosition

ActionApplication

  • Function activatePerformanceAssertion has been moved from NonStandardOperation class.

ConditionEvaluation

  • Function evaluateRelativeSpeed has been divided into part in ConditionEvaluation
    static auto evaluateRelativeSpeed(
    const std::string & from_entity_name, const std::string & to_entity_name) -> Eigen::Vector3d
    {
    if (core->isEntityExist(from_entity_name) && core->isEntityExist(to_entity_name)) {
    return core->relativeSpeed(from_entity_name, to_entity_name);
    } else {
    return Eigen::Vector3d::Constant(std::numeric_limits<double>::quiet_NaN());
    }
    }

    and part in API
    auto API::relativeSpeed(const std::string & from_entity_name, const std::string & to_entity_name)
    -> Eigen::Vector3d
    {
    auto velocity = [](const auto & entity) -> Eigen::Vector3d {
    auto direction = [](const auto & q) -> Eigen::Vector3d {
    return Eigen::Quaternion(q.w, q.x, q.y, q.z) * Eigen::Vector3d::UnitX();
    };
    return direction(entity.getMapPose().orientation) * entity.getCurrentTwist().linear.x;
    };
    const auto & observer = getEntity(from_entity_name);
    const auto & observed = getEntity(to_entity_name);
    const Eigen::Matrix3d rotation =
    math::geometry::getRotationMatrix(observer.getMapPose().orientation);
    return rotation.transpose() * velocity(observed) - rotation.transpose() * velocity(observer);
    }
  • Function evaluateTimeHeadaway has been divided into part in ConditionEvaluation
    static auto evaluateTimeHeadway(
    const std::string & from_entity_name, const std::string & to_entity_name) -> double
    {
    if (core->isEntityExist(from_entity_name) && core->isEntityExist(to_entity_name)) {
    if (const auto time_headway = core->timeHeadway(from_entity_name, to_entity_name)) {
    return time_headway.value();
    }
    }
    return std::numeric_limits<double>::quiet_NaN();
    }

    and part in API
    auto API::timeHeadway(const std::string & from_entity_name, const std::string & to_entity_name)
    -> std::optional<double>
    {
    if (from_entity_name != to_entity_name) {
    const auto & from_entity = getEntity(from_entity_name);
    const auto & to_entity = getEntity(to_entity_name);
    if (const auto relative_pose =
    pose::relativePose(from_entity.getMapPose(), to_entity.getMapPose());
    relative_pose && relative_pose->position.x <= 0) {
    const double time_headway =
    (relative_pose->position.x * -1.0) / to_entity.getCurrentTwist().linear.x;
    return std::isnan(time_headway) ? std::numeric_limits<double>::infinity() : time_headway;
    }
    }
    return std::nullopt;
    }
  • Some functions have been moved from NonStandardOperation
    • evaluateCurrentState
    • evaluateRelativeHeading

TrafficLightsOperation

  • Some functions have been moved from NonStandardOperation
    • setConventionalTrafficLightsState
    • setConventionalTrafficLightConfidence
    • getConventionalTrafficLightsComposedState
    • compareConventionalTrafficLightsState
    • resetConventionalTrafficLightPublishRate
    • setV2ITrafficLightsState
    • resetV2ITrafficLightPublishRate

Syntax

Important

Because of the changes listed in SimulatorCore, many openscenario_interpreter syntax classes had to be adjusted.
For most of the syntax classes the changes were limited only to changing the parent class in inheritance structure, or just using the new functions from SimulatorCore rather than the old ones.

DistanceCondition

Many changes have been applied to DistanceCondition of openscenario_interpreter. Most of these changes are simplifications that don't use the overloaded lambda functions and visitors, but rather just use newly developed SimulatorCore::DistanceConditionEvaluation member functions.
For example the function DistanceCondition::distance<CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, false> has been changed from

template <>
auto DistanceCondition::distance<
CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined,
false>(const EntityRef & triggering_entity, const Position & position) -> double
{
return apply<double>(
overload(
[&](const WorldPosition & position) {
const auto relative_world = makeNativeRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z);
},
[&](const RelativeWorldPosition & position) {
const auto relative_world = makeNativeRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z);
},
[&](const RelativeObjectPosition & position) {
const auto relative_world = makeNativeRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z);
},
[&](const LanePosition & position) {
const auto relative_world = makeNativeRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z);
}),
position);
}

to
template <>
auto DistanceCondition::distance<
CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined,
false>(const EntityRef & triggering_entity, const Position & position) -> double
{
return euclideanDistance(triggering_entity, static_cast<NativeWorldPosition>(position));
}

The simplification comes from reducing the overloaded lambdas that have identical implementations to just one function call.

ReachPositionCondition

Similarly to DistanceCondition the structure has been reworked to not use overloaded lambda functions and visitors, but rather directly call distance function.

Distance calculation in traffic_simulator

For simplicity some distance calculation functions have been added to traffic_simulator API so that openscenario_interpreter did not implement distance calculations but could use these functions here

auto laneletRelativeYaw(const std::string & entity_name, const LaneletPose & lanelet_pose) const
-> std::optional<double>;
auto timeHeadway(const std::string & from_entity_name, const std::string & to_entity_name)
-> std::optional<double>;
auto boundingBoxDistance(const std::string & from_entity_name, const std::string & to_entity_name)
-> std::optional<double>;
auto relativePose(const std::string & from_entity_name, const std::string & to_entity_name)
-> std::optional<geometry_msgs::msg::Pose>;
auto relativePose(
const std::string & from_entity_name, const geometry_msgs::msg::Pose & to_map_pose)
-> std::optional<geometry_msgs::msg::Pose>;
auto relativePose(
const geometry_msgs::msg::Pose & from_map_pose, const std::string & to_entity_name)
-> std::optional<geometry_msgs::msg::Pose>;
auto relativeSpeed(const std::string & from_entity_name, const std::string & to_entity_name)
-> Eigen::Vector3d;
auto countLaneChanges(
const std::string & from_entity_name, const std::string & to_entity_name,
const RoutingConfiguration & routing_configuration) const -> std::optional<std::pair<int, int>>;
auto boundingBoxRelativePose(
const std::string & from_entity_name, const geometry_msgs::msg::Pose & to_map_pose)
-> std::optional<geometry_msgs::msg::Pose>;
auto boundingBoxRelativePose(
const std::string & from_entity_name, const std::string & to_entity_name)
-> std::optional<geometry_msgs::msg::Pose>;
auto laneletDistance(
const std::string & from_entity_name, const std::string & to_entity_name,
const RoutingConfiguration & routing_configuration) -> LaneletDistance;
auto laneletDistance(
const std::string & from_entity_name, const LaneletPose & to_lanelet_pose,
const RoutingConfiguration & routing_configuration) -> LaneletDistance;
auto laneletDistance(
const LaneletPose & from_lanelet_pose, const std::string & to_entity_name,
const RoutingConfiguration & routing_configuration) -> LaneletDistance;
auto boundingBoxLaneletDistance(
const std::string & from_entity_name, const std::string & to_entity_name,
const RoutingConfiguration & routing_configuration) -> LaneletDistance;
auto boundingBoxLaneletDistance(
const std::string & from_entity_name, const LaneletPose & to_lanelet_pose,
const RoutingConfiguration & routing_configuration) -> LaneletDistance;

EntityBase (traffic_simulator)

requestSynchronize

In this PR additionally to all other changes, the EntityBase::requestSynchronize function has been refactored in order to make it easier to read and understand.
Most of the logic code was kept unchanged, but some reformating was applied to use the init-statement to declare variables inside the if statements which in the same time checks whether the value is correct.
What is more, a check whether the entity this synchronize request is applied on is an Ego entity, has been moved to overloaded member function of EgoEntity class here

auto EgoEntity::requestSynchronize(
const std::string & /*target_name*/, const LaneletPose & /*target_sync_pose*/,
const LaneletPose & /*entity_target*/, const double /*target_speed*/, const double /*tolerance*/)
-> bool
{
THROW_SYNTAX_ERROR("Request synchronize is only for non-ego entities.");
}

References

INTERNAL LINK 1
INTERNAL LINK 2

Destructive Changes

--

Known Limitations

--

dmoszynski and others added 18 commits July 3, 2024 17:10
…lized functions for distance calculations for each coordinate system
…ded-to-entity-base' into ref/RJD-1057-improve-responsibility-simulator-core-api
…ded-to-entity-base-refactor' into ref/RJD-1057-improve-responsibility-simulator-core-api
Signed-off-by: Mateusz Palczuk <[email protected]>
Signed-off-by: Mateusz Palczuk <[email protected]>
…ze(), guarantee canonicalization of input in API, add exceptions to canonicalize()
@dmoszynski dmoszynski self-assigned this Aug 6, 2024
@yamacir-kit yamacir-kit deleted the branch master September 18, 2024 01:43
@yamacir-kit yamacir-kit deleted the ref/RJD-1057-improve-responsibility-simulator-core-api branch September 18, 2024 01:45
@dmoszynski dmoszynski restored the ref/RJD-1057-improve-responsibility-simulator-core-api branch September 23, 2024 09:27
@dmoszynski dmoszynski reopened this Oct 14, 2024
…ded-to-entity-base-refactor' into ref/RJD-1057-improve-responsibility-simulator-core-api
…ded-to-entity-base-refactor' into ref/RJD-1057-improve-responsibility-simulator-core-api
Copy link

@HansRobo HansRobo reopened this Apr 17, 2025
Copy link

Checklist for reviewers ☑️

All references to "You" in the following text refer to the code reviewer.

  • Is this pull request written in a way that is easy to read from a third-party perspective?
  • Is there sufficient information (background, purpose, specification, algorithm description, list of disruptive changes, and migration guide) in the description of this pull request?
  • If this pull request contains a destructive change, does this pull request contain the migration guide?
  • Labels of this pull request are valid?
  • All unit tests/integration tests are included in this pull request? If you think adding test cases is unnecessary, please describe why and cross out this line.
  • The documentation for this pull request is enough? If you think adding documents for this pull request is unnecessary, please describe why and cross out this line.

@HansRobo HansRobo changed the base branch from RJD-1057-remove-functions-forwarded-to-entity-base-refactor to master April 17, 2025 04:24
@yamacir-kit
Copy link
Collaborator

@TauTheLepton @dmoszynski
Of the changes included in this pull request, the changes to SimulatorCore included in #1581 are not acceptable. The reasons are:

  • The idea that removing perfect forwarding improves readability is simply a matter of the pull request author's preference. (the usage of perfect forwarding in SimulatorCore is a well-known function alias idiom.)
  • By dropping perfect forwarding, it is no longer possible to support overloading of traffic_simulator::API member functions all together.
  • There is no technical advantage about reducing the use of templates. (Note: The current SimulatorCore code uses SFINAE heavily because the C++ standard adopted at the time of implementation, C++14, did not have if constexpr. if constexpr can be used to rewrite this elegantly.)

Simply put, changes that do not fall under “improve the responsibility division” should be reverted.


Note: SimulatorCore, which is obviously a redundant layer, is intended to express the concept of OpenSCENARIO XML 1.3.1 6.1.5 “Abstract ASAM OpenSCENARIO architecture” in code. The names of the member functions beginning with apply / evaluate are derived exactly from the figure in this section. In the future, when scenario_simulator_v2 considers OSI (Open Simulation Interface) support, this layer may become important.

TauTheLepton and others added 4 commits May 6, 2025 10:49
…-responsibility-simulator-core-api

Signed-off-by: Mateusz Palczuk <[email protected]>
The implementations of the removed functions have already been removed and leaving these in a header was an oversight

Signed-off-by: Mateusz Palczuk <[email protected]>
…-responsibility-simulator-core-api

Signed-off-by: Mateusz Palczuk <[email protected]>
Copy link

Failure optional scenarios

Note

This is an experimental check and does not block merging the pull-request.
But, please be aware that this may indicate a regression.

scenario failed: execution_time_test
      <failure type="SimulationFailure" message="CustomCommandAction typed &quot;exitFailure&quot; was triggered by the named Conditions {&quot;update time checker&quot;, &quot;avoid startup&quot;}: {&quot;update time checker&quot;: Is the /simulation/interpreter/execution_time/update (= 0.006380000000000000254241072639) is greaterThan 0.005?}, {&quot;avoid startup&quot;: Is the simulation time (= 1.800000000000000932587340685131) is greaterThan 1.000000000000000000000000000000?}" />

@TauTheLepton
Copy link
Contributor Author

TauTheLepton commented May 15, 2025

@yamacir-kit

@TauTheLepton @dmoszynski
Of the changes included in this pull request, the changes to SimulatorCore included in #1581 are not acceptable. The reasons are:

  • The idea that removing perfect forwarding improves readability is simply a matter of the pull request author's preference. (the usage of perfect forwarding in SimulatorCore is a well-known function alias idiom.)
  • By dropping perfect forwarding, it is no longer possible to support overloading of traffic_simulator::API member functions all together.
  • There is no technical advantage about reducing the use of templates. (Note: The current SimulatorCore code uses SFINAE heavily because the C++ standard adopted at the time of implementation, C++14, did not have if constexpr. if constexpr can be used to rewrite this elegantly.)

Simply put, changes that do not fall under "improve the responsibility division" should be reverted.


Note: SimulatorCore, which is obviously a redundant layer, is intended to express the concept of OpenSCENARIO XML 1.3.1 6.1.5 "Abstract ASAM OpenSCENARIO architecture" in code. The names of the member functions beginning with apply / evaluate are derived exactly from the figure in this section. In the future, when scenario_simulator_v2 considers OSI (Open Simulation Interface) support, this layer may become important.

Before making any changes, we would like to explain what were our intentions and what are some of the benefits of the changes we have proposed.

Based on that and your feedback, we will then change so that the code is as expected and in line with any assumptions.

Overview

We realize some changes made here are subjective and some changes may break some existing practices.
This is why we want to share the whole idea behind these changes.
This PR can also be seen as our proposition of changes, as this is not strictly necessary, but we believe these are valuable additions.
As this PR is the last of 5 main PRs refactoring the traffic simulator it summarizes and organizes the changes made in all the previous PRs.

Removing templates

We have observed that the SimulatorCore uses a combination of variadic templates and explicit arguments.
Some functions use perfect forwarding while others use only explicit argument.
This practice is not consistent in any way, some functions forward parameter pack where the parameter pack does not hold anything, because the called functions does not take any parameters.
The functions using variadic templates in theory can call some function underneath using different arguments without the need to write additional code. However, we have noticed this was not actually used even once. All underlying functions called with the parameter pack accept only one set of arguments, as there are no overloads available. This has been proven by the implementation in this PR which converted all functions to use explicit arguments and everything is still working with no additional functions defined.
Our motivation for removing the variadic templates was to increase readability. This change did not add any technical advantage, but it also did not make any sacrifices in the current implementation - like defining multiple function overloads.

What is more, we removed variadic templates with perfect arguments forwarding only in these functions were this did not add any value.

Current `master` code examples

Usage of variadic templates + perfect forwarding

template <typename... Ts>
static auto applyAddEntityAction(Ts &&... xs) -> decltype(auto)
{
return core->spawn(std::forward<decltype(xs)>(xs)...);
}

template <typename... Ts>
static auto applyDeleteEntityAction(Ts &&... xs)
{
return core->despawn(std::forward<decltype(xs)>(xs)...);
}

Usage of explicit arguments

static auto makeNativeRelativeWorldPosition(
const std::string & from_entity_name, const NativeWorldPosition & to_map_pose)
{
if (const auto from_entity = core->getEntityPointer(from_entity_name)) {
if (
const auto relative_pose =
traffic_simulator::pose::relativePose(from_entity->getMapPose(), to_map_pose)) {
return relative_pose.value();
}
}
return traffic_simulator::pose::quietNaNPose();
}

static auto makeNativeBoundingBoxRelativeWorldPosition(
const std::string & from_entity_name, const NativeWorldPosition & to_map_pose)

static auto evaluateLateralRelativeLanes(
const std::string & from_entity_name, const std::string & to_entity_name,
const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined) -> int

Structure changes

Distance evaluation

We have noticed many functions in CoordinateSystemConversion actually are used solely for implicit distance calculations (e.g. relative pose was only used to calculate length of the vector3 - distance).

For this reason and to make the code more expressive we changed these functions to utilize API distance functions and moved them to DistanceConditionEvaluation class (with changed names).

Code example

Current version

Function

static auto makeNativeRelativeWorldPosition(
const std::string & from_entity_name, const std::string & to_entity_name)
{
if (const auto from_entity = core->getEntityPointer(from_entity_name)) {
if (const auto to_entity = core->getEntityPointer(to_entity_name)) {
if (
const auto relative_pose = traffic_simulator::pose::relativePose(
from_entity->getMapPose(), to_entity->getMapPose()))
return relative_pose.value();
}
}
return traffic_simulator::pose::quietNaNPose();
}

Usage
template <>
auto DistanceCondition::distance<
CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined,
false>(const EntityRef & triggering_entity, const Position & position) -> double
{
return apply<double>(
overload(
[&](const WorldPosition & position) {
const auto relative_world = makeNativeRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z);
},
[&](const RelativeWorldPosition & position) {
const auto relative_world = makeNativeRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z);
},
[&](const RelativeObjectPosition & position) {
const auto relative_world = makeNativeRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z);
},
[&](const LanePosition & position) {
const auto relative_world = makeNativeRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z);
}),
position);
}

Proposed changes

Function

template <typename FirstType, typename SecondType>
static auto euclideanDistance(
const FirstType & from_pose_or_entity_name, const SecondType & to_pose_or_entity_name)
-> double
{
if (prerequisite(from_pose_or_entity_name, to_pose_or_entity_name)) {
if (
const auto pose = core->relativePose(from_pose_or_entity_name, to_pose_or_entity_name)) {
return hypot(pose.value().position.x, pose.value().position.y, pose.value().position.z);
}
}
return std::numeric_limits<double>::quiet_NaN();
}

Usage
template <>
auto DistanceCondition::distance<
CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined,
false>(const EntityRef & triggering_entity, const Position & position) -> double
{
return euclideanDistance(triggering_entity, static_cast<NativeWorldPosition>(position));
}

Functionality changes

Entity checks

We have changed some functionality in the SimulatorCore.
One very common operation in SimulatorCore is referencing entities by their names.
We have added a check that verifies that the entity exists before taking any further action.
Some of these checks were previously implemented in the openscenario interpreter, while others in the API.
We wanted to make one layer responsible of performing this check - SimulatorCore. This was in part achieved by transitioning from using API functions that used to take entity name to using getEntity and getEntityPointer API member functions.

For this change we have added prerequisite function.

This change is very similar to transitioning to using LaneletPose (instead of canonicalized) in communication with API - the canonicalization is responsibility of API.

Code examples

Current version

static auto makeNativeRelativeWorldPosition(
const std::string & from_entity_name, const std::string & to_entity_name)
{
if (const auto from_entity = core->getEntityPointer(from_entity_name)) {
if (const auto to_entity = core->getEntityPointer(to_entity_name)) {
if (
const auto relative_pose = traffic_simulator::pose::relativePose(
from_entity->getMapPose(), to_entity->getMapPose()))
return relative_pose.value();
}
}
return traffic_simulator::pose::quietNaNPose();
}

static auto makeNativeBoundingBoxRelativeLanePosition(
const std::string & from_entity_name, const std::string & to_entity_name,
const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined)
{
if (const auto from_entity = core->getEntityPointer(from_entity_name)) {
if (const auto to_entity = core->getEntityPointer(to_entity_name)) {
if (const auto from_lanelet_pose = from_entity->getCanonicalizedLaneletPose()) {
if (const auto to_lanelet_pose = to_entity->getCanonicalizedLaneletPose()) {
return makeNativeBoundingBoxRelativeLanePosition(
from_lanelet_pose.value(), from_entity->getBoundingBox(), to_lanelet_pose.value(),
to_entity->getBoundingBox(), routing_algorithm);
}
}
}
}
return traffic_simulator::pose::quietNaNLaneletPose();
}

Proposed changes

template <typename FirstType, typename SecondType>
static auto euclideanDistance(
const FirstType & from_pose_or_entity_name, const SecondType & to_pose_or_entity_name)
-> double
{
if (prerequisite(from_pose_or_entity_name, to_pose_or_entity_name)) {
if (
const auto pose = core->relativePose(from_pose_or_entity_name, to_pose_or_entity_name)) {
return hypot(pose.value().position.x, pose.value().position.y, pose.value().position.z);
}
}
return std::numeric_limits<double>::quiet_NaN();
}

template <typename FirstType, typename SecondType>
static auto lateralEntityDistance(
const FirstType & from_pose_or_entity_name, const SecondType & to_pose_or_entity_name)
-> double
{
if (prerequisite(from_pose_or_entity_name, to_pose_or_entity_name)) {
if (
const auto pose = core->relativePose(from_pose_or_entity_name, to_pose_or_entity_name)) {
return pose.value().position.y;
}
}
return std::numeric_limits<double>::quiet_NaN();
}

Note

This change to add entity checks in SimulatorCore was also a factor in removing some of the variadic templates.

Code example

Current version

template <typename... Ts>
static auto evaluateCollisionCondition(Ts &&... xs) -> bool
{
return core->checkCollision(std::forward<decltype(xs)>(xs)...);
}

Proposed changes

static auto evaluateCollisionCondition(
const std::string & first_entity_name, const std::string & second_entity_name) -> bool
{
if (core->isEntityExist(first_entity_name) && core->isEntityExist(second_entity_name)) {
return core->checkCollision(first_entity_name, second_entity_name);
} else {
return false;
}
}

Changes visualized in functions signatures

In hidden sections are all function signatures before and after the proposed changes.

You can see that the argument forwarding with variadic templates was removed from all subclasses except ActionApplication which is the only subclass actually utilizing some function overloads in API.
In the "before" section you can see the argument forwarding with variadic templates is sometimes used and other times it is not and there is no rule to this (these functions are not all getters or evaluate functions or anything like that).

All functions signatures before changes

before_changes0
before_changes1
before_changes2
before_changes3
before_changes4

All function signatures after changes

after_changes0
after_changes1
after_changes2
after_changes3
after_changes4
after_changes5
after_changes6

Summary

Functions that can be reverted with no functionality loss

These functions can be reverted to use variadic template, although all of them can be called with only one set of parameters, as the functions called with parameter pack don't have any overloads.

  • activate
  • applyAddEntityAction
  • applyDeleteEntityAction
  • applyFollowTrajectoryAction
  • applyWalkStraightAction
  • evaluateSimulationTime
  • evaluateCurrentState
  • sendCooperateCommand
  • setConventionalTrafficLightsState
  • setConventionalTrafficLightConfidence
  • getConventionalTrafficLightsComposedState
  • compareConventionalTrafficLightsState
  • resetConventionalTrafficLightPublishRate
  • setV2ITrafficLightsState
  • resetV2ITrafficLightPublishRate

Functions which after reverting will loose functionality - we encourage to leave them changed

These function - if reverted to using variadic template (state from before this PR) - would loose some functionality

  • evaluateCollisionCondition
    • This function contains additional check whether entities to check collision even exist.

@TauTheLepton TauTheLepton marked this pull request as ready for review May 20, 2025 08:23
@yamacir-kit
Copy link
Collaborator

yamacir-kit commented May 22, 2025

@TauTheLepton
Your observation is correct for the current code base, but not certain for the future.
openscenario_interpreter is a DSL implementation based on a specification developed by others, not us. Therefore, it is very likely that future updates of the specification will add new Actions/Conditions.

About "Removing templates

It is true, as you say, that the perfect forwarding destination function may not be overloaded or may have no arguments.
However, it is important to note that perfect forwarding is also responsible for stating that the argument lineup has not been changed. Removing a perfect forwarding because there is no overload violates the “don't repeat yourself” principle.

Therefore, this change is not acceptable.

About "Structure changes / Distance evaluation"

Distance calculations are the responsibility of syntax::DistanceCondition and syntax::RelativeDistanceCondition.
The reason why syntax::DistanceCondition::distance and syntax::RelativeDistanceCondition::distance are static member functions is to consolidate distance calculations in the OpenSCENARIO XML style. In other words, the “Structure changes / Distance evaluation” change obscures these responsibilities.

While it is true that CoordinateSystemConversion is currently only used for distance calculations, these will need to be implemented again when actions/conditions requiring coordinate conversion are added to the standard in the future.

Therefore, this change is not acceptable.

"Functionality changes / Entity checks"

This change is reasonable and may be retained. However, please reconsider the function names. It is not possible to infer what is being processed from the function name.

…-responsibility-simulator-core-api

Signed-off-by: Mateusz Palczuk <[email protected]>
… same as requestAcquirePosition

Signed-off-by: Mateusz Palczuk <[email protected]>
…-responsibility-simulator-core-api

Signed-off-by: Mateusz Palczuk <[email protected]>
Signed-off-by: Mateusz Palczuk <[email protected]>

Bring back distance condition evaluation in syntax (taken from commit "e6ffb819399842b6b3f71a7de816f36fcc01cfe0")

Signed-off-by: Mateusz Palczuk <[email protected]>

Move entity check to SimulatorCore scope and use in this class

Signed-off-by: Mateusz Palczuk <[email protected]>

Bring back distance condition evaluation fully + lateral lane changes in syntax (taken from commit "e6ffb819399842b6b3f71a7de816f36fcc01cfe0")

Bring back `evaluateLateralRelativeLanes` to `SimulatorCore::CoordinateSystemConversion`

Signed-off-by: Mateusz Palczuk <[email protected]>

Remove `SimulatorCore::DistanceConditionEvaluation` class

Signed-off-by: Mateusz Palczuk <[email protected]>

Bring back return type deduction

Signed-off-by: Mateusz Palczuk <[email protected]>

Remove route clear in `applyAcquirePositionAction` - make implementation mirror the master

Signed-off-by: Mateusz Palczuk <[email protected]>

Bring back perfect forwarding for API constructor

Signed-off-by: Mateusz Palczuk <[email protected]>

Move `API::boundingBoxRelativePose` to be groupped with similar functions

Signed-off-by: Mateusz Palczuk <[email protected]>

Remove lanelet distance function from API

Signed-off-by: Mateusz Palczuk <[email protected]>

Remove lanelet distance functions

Signed-off-by: Mateusz Palczuk <[email protected]>
@TauTheLepton
Copy link
Contributor Author

TauTheLepton commented Jun 9, 2025

@yamacir-kit cc @dmoszynski

In the commit 8ecd226, we have changed the following

  • We have reverted distance calculations changes and restored the previous approach:
    • Note: During the development, we noticed that reverting these changes required all of the SimulatorCore::makeNative* functions to return pose::quietNaNPose() - as it was before, in case of failure, e.g. if any of the objects do not exist.

      • The already reverted changes in PR 5/5 ensured that exceptions were thrown in such cases. This was possible because the SimulatorCore::makeNative... functions were not used for distance evaluation, but such evaluations were done by using separate dedicated functions which have been removed in this commit. See:
    • To revert this according to the responsibility division we are trying to achieve, we have developed a set of relative pose functions in API that are called in SimulatorCore::CoordinateSystemConversion functions, see here.

  • Some templates and return type deductions that were removed earlier were brought back.
  • We have added SimulatorCore::doesEntityExistIfIsEntityName functions for conditional entity checks and used them in SimulatorCore (instead of the removed DistanceConditionEvaluation::prerequisite)

What hasn't changed

  • The conversion functions were changed to not use templates
    • convert<> has been changed to convertToNativeLanePosition and convertToNativeWorldPosition
      • Please let us know what you think of this change 🙇‍♂️
  • Some functions have been moved around in the SimulatorCore subclasses to make them more grouped
    • E.g. activateNonUserDefinedControllers was moved directly to SimulatorCore
    • Or traffic light functions were moved to new SimulatorCore subclass TrafficLightsOperation
    • Functions in SimulatorCore::ConditionEvaluation all check whether the entity exists and if it does not, they return a neutral value like NaN
    • Functions in SimulatorCore::CoordinateSystemConversion behave the same as above
    • Functions in ActionApplication and NonStandardOperation do not perform these checks, and they will throw errors (the traffic_simulator will throw errors when an entity does not exist)
    • Due to these changes, some syntax classes had to have their inheritance modified
  • To achieve responsibility division, functionality of some SimulatorCore functions has been moved to new functions in API and these new functions are called from SimulatorCore

Copy link

@HansRobo
Copy link
Member

Hi @TauTheLepton ( CC: @dmoszynski @yamacir-kit @hakuturu583 @YoshinoriTsutake )

First of all, thank you for your significant effort and the extensive work you've put into this pull request. We truly appreciate the time and dedication you invested in tackling the complex task of improving the role separation between traffic_simulator and openscenario_interpreter.

This PR sparked a deep and necessary discussion within the team about our core architectural principles. Through these conversations, we've had the opportunity to clarify and reaffirm some fundamental design philosophies that we believe are crucial for the long-term health and maintainability of our codebase.

Specifically, we've solidified our stance on two key points:

  1. Strict Separation of Concerns: We have reaffirmed our design philosophy that traffic_simulator should serve as a provider of robust, primitive functionalities. The responsibility for composing these primitives to achieve complex behaviors should lie with the client (e.g., openscenario_interpreter). This PR helped us realize that moving client-side logic into the simulator blurs this critical boundary more than we are comfortable with.

  2. The Importance of Type Safety: The use of CanonicalizedLaneletPose is a deliberate design choice to enforce correctness at the type level. It guarantees that any pose passed to our core APIs is already in a valid, canonical form. Your proposal to use LaneletPose and handle canonicalization internally made us re-evaluate this, and we've concluded that preserving this compile-time safety net is a high priority for us to prevent runtime errors and ensure system robustness.

Based on these clarified principles, we've concluded that the approach taken in this PR, while well-intentioned, moves us in a direction that diverges from our long-term architectural goals. Therefore, we have decided to close this pull request.

Please understand that this decision is not a reflection on the quality or effort of your work. On the contrary, your PR was invaluable. It forced us to have this essential conversation and to solidify principles that were previously not explicitly documented. We couldn't have reached this level of clarity without your contribution.

Thank you again for your hard work and for helping us sharpen our vision for the project.

Best regards,
The Team

@HansRobo HansRobo closed this Jun 16, 2025
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bump major If this pull request merged, bump major version of the scenario_simulator_v2 refactor
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants