From 1abe1bda84869f381d0d3b6f5b64e8e7bd5636cc Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 21 May 2024 15:05:48 +0900 Subject: [PATCH 01/25] Add new struct `TimeToCollisionCondition` Signed-off-by: yamacir-kit --- .../syntax/time_to_collision_condition.hpp | 126 ++++++++++++++++++ .../src/syntax/entity_condition.cpp | 3 +- 2 files changed, 128 insertions(+), 1 deletion(-) create mode 100644 openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp new file mode 100644 index 00000000000..aff3deeec54 --- /dev/null +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -0,0 +1,126 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__TIME_TO_COLLISION_CONDITION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__TIME_TO_COLLISION_CONDITION_HPP_ + +#include +#include +#include + +namespace openscenario_interpreter +{ +inline namespace syntax +{ +/* + TimeToCollisionCondition + + The currently predicted time to collision of a triggering entity/entities + and either a reference entity or an explicit position is compared to a given + time value. Time to collision is calculated as the distance divided by the + relative speed. Acceleration of entities is not taken into consideration. + For the relative speed calculation the same coordinate system and relative + distance type applies as for the distance calculation. If the relative speed + is negative, which means the entity is moving away from the position / the + entities are moving away from each other, then the time to collision cannot + be predicted and the condition evaluates to false. The logical operator for + comparison is defined by the rule attribute. The property "alongRoute" is + deprecated. If "coordinateSystem" or "relativeDistanceType" are set, + "alongRoute" is ignored. + + XSD 1.3 Representation + + + + + + + + + deprecated + + + + + + + + + + +*/ +struct TimeToCollisionCondition : private SimulatorCore::ConditionEvaluation +{ + const Boolean freespace; + + const Rule rule; + + const Double value; + + const RelativeDistanceType relative_distance_type; + + const CoordinateSystem coordinate_system; + + const RoutingAlgorithm routing_algorithm; + + const TriggeringEntities triggering_entities; + + std::vector evaluations; + + explicit TimeToCollisionCondition( + const pugi::xml_node & node, Scope & scope, const TriggeringEntities & triggering_entities) + : freespace(readAttribute("freespace", node, scope)), + rule(readAttribute("rule", node, scope)), + value(readAttribute("value", node, scope)), + relative_distance_type( + readAttribute("relativeDistanceType", node, scope)), + coordinate_system( + readAttribute("coordinateSystem", node, scope, CoordinateSystem::entity)), + routing_algorithm(readAttribute( + "routingAlgorithm", node, scope, RoutingAlgorithm::undefined)), + triggering_entities(triggering_entities), + evaluations(triggering_entities.entity_refs.size(), Double::nan()) + { + } + + auto description() const -> String + { + auto description = std::stringstream(); + + description << triggering_entities.description() << "'s time-to-collision to given entity " + << "TODO-RELATIVE-DISTANCE-TARGET" + << " = "; + + print_to(description, evaluations); + + description << " " << rule << " " << value << "?"; + + return description.str(); + } + + auto evaluate() + { + evaluations.clear(); + + return asBoolean(triggering_entities.apply([this](auto && triggering_entity) { + [[deprecated]] auto evaluateTimeToCollision = [](auto &&...) { return Double(); }; + evaluations.push_back(evaluateTimeToCollision(triggering_entity, "TODO")); + return std::invoke(rule, evaluations.back(), value); + })); + } +}; +} // namespace syntax +} // namespace openscenario_interpreter + +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__TIME_TO_COLLISION_CONDITION_HPP_ diff --git a/openscenario/openscenario_interpreter/src/syntax/entity_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/entity_condition.cpp index 9577b8f9453..a0b9aca1a00 100644 --- a/openscenario/openscenario_interpreter/src/syntax/entity_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/entity_condition.cpp @@ -22,6 +22,7 @@ #include #include #include +#include namespace openscenario_interpreter { @@ -36,7 +37,7 @@ EntityCondition::EntityCondition( std::make_pair( "CollisionCondition", [&](const auto & node) { return make< CollisionCondition>(node, scope, triggering_entities); }), std::make_pair( "OffroadCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), std::make_pair( "TimeHeadwayCondition", [&](const auto & node) { return make< TimeHeadwayCondition>(node, scope, triggering_entities); }), - std::make_pair( "TimeToCollisionCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), + std::make_pair( "TimeToCollisionCondition", [&](const auto & node) { return make< TimeToCollisionCondition>(node, scope, triggering_entities); }), std::make_pair( "AccelerationCondition", [&](const auto & node) { return make< AccelerationCondition>(node, scope, triggering_entities); }), std::make_pair( "StandStillCondition", [&](const auto & node) { return make< StandStillCondition>(node, scope, triggering_entities); }), std::make_pair( "SpeedCondition", [&](const auto & node) { return make< SpeedCondition>(node, scope, triggering_entities); }), From 3a6c2b9a4981fb311fdd6314d38f7f723a4bdc6f Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 21 May 2024 15:26:31 +0900 Subject: [PATCH 02/25] Add new struct `TimeToCollisionConditionTarget` Signed-off-by: yamacir-kit --- .../syntax/time_to_collision_condition.hpp | 11 ++-- .../time_to_collision_condition_target.hpp | 54 +++++++++++++++++++ 2 files changed, 61 insertions(+), 4 deletions(-) create mode 100644 openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition_target.hpp diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp index aff3deeec54..6bb98167f53 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -17,6 +17,7 @@ #include #include +#include #include namespace openscenario_interpreter @@ -24,7 +25,7 @@ namespace openscenario_interpreter inline namespace syntax { /* - TimeToCollisionCondition + TimeToCollisionCondition 1.3 The currently predicted time to collision of a triggering entity/entities and either a reference entity or an explicit position is compared to a given @@ -39,8 +40,6 @@ inline namespace syntax deprecated. If "coordinateSystem" or "relativeDistanceType" are set, "alongRoute" is ignored. - XSD 1.3 Representation - @@ -62,6 +61,8 @@ inline namespace syntax */ struct TimeToCollisionCondition : private SimulatorCore::ConditionEvaluation { + const TimeToCollisionConditionTarget time_to_collision_condition_target; + const Boolean freespace; const Rule rule; @@ -80,7 +81,9 @@ struct TimeToCollisionCondition : private SimulatorCore::ConditionEvaluation explicit TimeToCollisionCondition( const pugi::xml_node & node, Scope & scope, const TriggeringEntities & triggering_entities) - : freespace(readAttribute("freespace", node, scope)), + : time_to_collision_condition_target( + readElement("TimeToCollisionConditionTarget", node, scope)), + freespace(readAttribute("freespace", node, scope)), rule(readAttribute("rule", node, scope)), value(readAttribute("value", node, scope)), relative_distance_type( diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition_target.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition_target.hpp new file mode 100644 index 00000000000..960a87e9660 --- /dev/null +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition_target.hpp @@ -0,0 +1,54 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__TIME_TO_COLLISION_CONDITION_TARGET_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__TIME_TO_COLLISION_CONDITION_TARGET_HPP_ + +#include +#include +#include +#include + +namespace openscenario_interpreter +{ +inline namespace syntax +{ +/* + TimeToCollisionConditionTarget 1.3 + + Target position used in the TimeToCollisionCondition. Can be defined as + either an explicit position, or the position of a reference entity. + + + + + + + +*/ +struct TimeToCollisionConditionTarget : public ComplexType +{ + explicit TimeToCollisionConditionTarget(const pugi::xml_node & node, Scope & scope) + // clang-format off + : ComplexType(choice(node, + std::make_pair( "Position", [&](auto && node) { return make< Position>(std::forward(node), scope); }), + std::make_pair("EntityRef", [&](auto && node) { return make(std::forward(node), scope); }))) + // clang-format on + { + } +}; +} // namespace syntax +} // namespace openscenario_interpreter + +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__TIME_TO_COLLISION_CONDITION_TARGET_HPP_ From 5447363cde632787022eb475ff1c4b8840357ce2 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 21 May 2024 16:16:53 +0900 Subject: [PATCH 03/25] Add new structs `RelativeSpeedCondition` and `DirectionalDimension` Signed-off-by: yamacir-kit --- .../syntax/directional_dimension.hpp | 108 ++++++++++++++++++ .../syntax/relative_speed_condition.hpp | 96 ++++++++++++++++ .../syntax/time_to_collision_condition.hpp | 6 +- .../src/syntax/entity_condition.cpp | 3 +- 4 files changed, 209 insertions(+), 4 deletions(-) create mode 100644 openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/directional_dimension.hpp create mode 100644 openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/directional_dimension.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/directional_dimension.hpp new file mode 100644 index 00000000000..6bafc12b920 --- /dev/null +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/directional_dimension.hpp @@ -0,0 +1,108 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__DIRECTIONAL_DIMENSION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__DIRECTIONAL_DIMENSION_HPP_ + +namespace openscenario_interpreter +{ +inline namespace syntax +{ +/* + DirectionalDimension (OpenSCENARIO XML 1.3) + + Defines the directions in the entity coordinate system. + + + + + + + + + + + + + + + +*/ +struct DirectionalDimension +{ + enum value_type { + /* + Longitudinal direction (along the x-axis). + */ + longitudinal, // NOTE: DEFAULT VALUE + + /* + Lateral direction (along the y-axis). + */ + lateral, + + /* + Vertical direction (along the z-axis). + */ + vertical, + }; + + value_type value; + + DirectionalDimension() = default; + + constexpr DirectionalDimension(value_type value) : value(value) {} + + constexpr operator value_type() const noexcept { return value; } + + friend auto operator>>(std::istream & istream, DirectionalDimension & datum) -> std::istream & + { + if (auto token = std::string(); istream >> token) { + if (token == "longitudinal") { + datum.value = DirectionalDimension::longitudinal; + return istream; + } else if (token == "lateral") { + datum.value = DirectionalDimension::lateral; + return istream; + } else if (token == "vertical") { + datum.value = DirectionalDimension::vertical; + return istream; + } else { + throw UNEXPECTED_ENUMERATION_VALUE_SPECIFIED(DirectionalDimension, token); + } + } else { + datum.value = DirectionalDimension::value_type(); + return istream; + } + } + + friend auto operator<<(std::ostream & ostream, const DirectionalDimension & datum) + -> std::ostream & + { + switch (datum) { + case DirectionalDimension::longitudinal: + return ostream << "longitudinal"; + case DirectionalDimension::lateral: + return ostream << "lateral"; + case DirectionalDimension::vertical: + return ostream << "vertical"; + default: + throw UNEXPECTED_ENUMERATION_VALUE_ASSIGNED(DirectionalDimension, datum); + } + } +}; +} // namespace syntax +} // namespace openscenario_interpreter + +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__DIRECTIONAL_DIMENSION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp new file mode 100644 index 00000000000..96d6223e9db --- /dev/null +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp @@ -0,0 +1,96 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_SPEED_CONDITION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_SPEED_CONDITION_HPP_ + +#include +#include +#include +#include + +namespace openscenario_interpreter +{ +inline namespace syntax +{ +/* + RelativeSpeedCondition 1.3 + + The current relative speed of a triggering entity/entities to a reference + entity is compared to a given value. The logical operator used for the + evaluation is defined by the rule attribute. If direction is used, only the + projection to that direction is used in the comparison, with the triggering + entity/entities as the reference. + + + + + + + +*/ +struct RelativeSpeedCondition : private SimulatorCore::ConditionEvaluation +{ + const EntityRef entity_ref; + + const Rule rule; + + const Double value; + + const DirectionalDimension direction; + + const TriggeringEntities triggering_entities; + + std::vector evaluations; + + explicit RelativeSpeedCondition( + const pugi::xml_node & node, Scope & scope, const TriggeringEntities & triggering_entities) + : entity_ref(readAttribute("entityRef", node, scope)), + rule(readAttribute("rule", node, scope)), + value(readAttribute("value", node, scope)), + direction(readAttribute("direction", node, scope)), + triggering_entities(triggering_entities), + evaluations(triggering_entities.entity_refs.size(), Double::nan()) + { + } + + auto description() const + { + auto description = std::stringstream(); + + description << triggering_entities.description() << "'s relative speed to given entity " + << entity_ref << " = "; + + print_to(description, evaluations); + + description << " " << rule << " " << value << "?"; + + return description.str(); + } + + auto evaluate() + { + evaluations.clear(); + + return asBoolean(triggering_entities.apply([this](auto && triggering_entity) { + [[deprecated]] auto evaluateRelativeSpeed = [](auto &&...) { return Double(); }; + evaluations.push_back(evaluateRelativeSpeed(triggering_entity, entity_ref)); + return std::invoke(rule, evaluations.back(), value); + })); + } +}; +} // namespace syntax +} // namespace openscenario_interpreter + +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_SPEED_CONDITION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp index 6bb98167f53..2e8eee42cb2 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -25,7 +25,7 @@ namespace openscenario_interpreter inline namespace syntax { /* - TimeToCollisionCondition 1.3 + TimeToCollisionCondition (OpenSCENARIO XML 1.3) The currently predicted time to collision of a triggering entity/entities and either a reference entity or an explicit position is compared to a given @@ -97,11 +97,11 @@ struct TimeToCollisionCondition : private SimulatorCore::ConditionEvaluation { } - auto description() const -> String + auto description() const { auto description = std::stringstream(); - description << triggering_entities.description() << "'s time-to-collision to given entity " + description << triggering_entities.description() << "'s time to collision to given entity " << "TODO-RELATIVE-DISTANCE-TARGET" << " = "; diff --git a/openscenario/openscenario_interpreter/src/syntax/entity_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/entity_condition.cpp index a0b9aca1a00..bf25305d994 100644 --- a/openscenario/openscenario_interpreter/src/syntax/entity_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/entity_condition.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include #include @@ -41,7 +42,7 @@ EntityCondition::EntityCondition( std::make_pair( "AccelerationCondition", [&](const auto & node) { return make< AccelerationCondition>(node, scope, triggering_entities); }), std::make_pair( "StandStillCondition", [&](const auto & node) { return make< StandStillCondition>(node, scope, triggering_entities); }), std::make_pair( "SpeedCondition", [&](const auto & node) { return make< SpeedCondition>(node, scope, triggering_entities); }), - std::make_pair( "RelativeSpeedCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), + std::make_pair( "RelativeSpeedCondition", [&](const auto & node) { return make< RelativeSpeedCondition>(node, scope, triggering_entities); }), std::make_pair("TraveledDistanceCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), std::make_pair( "ReachPositionCondition", [&](const auto & node) { return make< ReachPositionCondition>(node, scope, triggering_entities); }), std::make_pair( "DistanceCondition", [&](const auto & node) { return make< DistanceCondition>(node, scope, triggering_entities); }), From b09ca1fc3ce9a855ef46c7309419fc5700573e90 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 21 May 2024 18:04:41 +0900 Subject: [PATCH 04/25] Add static member function `ConditionEvaluation::evaluateRelativeSpeed` Signed-off-by: yamacir-kit --- .../reader/attribute.hpp | 11 +++++ .../simulator_core.hpp | 20 ++++++--- .../syntax/relative_speed_condition.hpp | 45 ++++++++++++++++--- 3 files changed, 64 insertions(+), 12 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/reader/attribute.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/reader/attribute.hpp index 06568802cbe..945e1a346a3 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/reader/attribute.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/reader/attribute.hpp @@ -22,6 +22,7 @@ #include #include #include +#include #include #include #include @@ -164,6 +165,16 @@ auto readAttribute(const std::string & name, const Node & node, const Scope & sc return value; } } + +template +auto readAttribute(const std::string & name, const Node & node, const Scope & scope, std::nullopt_t) +{ + if (node.attribute(name.c_str())) { + return std::make_optional(readAttribute(name, node, scope)); + } else { + return std::optional(); + } +} } // namespace reader } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index ed80b3e3879..79f5f7239d6 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -15,6 +15,7 @@ #ifndef OPENSCENARIO_INTERPRETER__SIMULATOR_CORE_HPP_ #define OPENSCENARIO_INTERPRETER__SIMULATOR_CORE_HPP_ +#include #include #include #include @@ -482,12 +483,6 @@ class SimulatorCore return core->getCurrentAccel(std::forward(xs)...).linear.x; } - template - static auto evaluateCollisionCondition(Ts &&... xs) -> bool - { - return core->checkCollision(std::forward(xs)...); - } - template static auto evaluateBoundingBoxEuclideanDistance(Ts &&... xs) // for RelativeDistanceCondition { @@ -500,6 +495,19 @@ class SimulatorCore } } + template + static auto evaluateCollisionCondition(Ts &&... xs) -> bool + { + return core->checkCollision(std::forward(xs)...); + } + + template + static auto evaluateRelativeSpeed(const T & x, const U & y) + { + using math::geometry::operator-; + return core->getCurrentTwist(x).linear - core->getCurrentTwist(y).linear; + } + template static auto evaluateSimulationTime(Ts &&... xs) -> double { diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp index 96d6223e9db..d535388c5dc 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp @@ -15,6 +15,7 @@ #ifndef OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_SPEED_CONDITION_HPP_ #define OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_SPEED_CONDITION_HPP_ +#include #include #include #include @@ -42,13 +43,26 @@ inline namespace syntax */ struct RelativeSpeedCondition : private SimulatorCore::ConditionEvaluation { + /* + Reference entity. + */ const EntityRef entity_ref; + /* + The operator (less, greater, equal). + */ const Rule rule; + /* + Relative speed value. Unit: [m/s]. Range: ]-inf..inf[. Relative speed is + defined as speed_rel = speed(triggering entity) - speed(reference entity) + */ const Double value; - const DirectionalDimension direction; + /* + Direction of the speed (if not given, the total speed is considered). + */ + const std::optional direction; const TriggeringEntities triggering_entities; @@ -59,7 +73,7 @@ struct RelativeSpeedCondition : private SimulatorCore::ConditionEvaluation : entity_ref(readAttribute("entityRef", node, scope)), rule(readAttribute("rule", node, scope)), value(readAttribute("value", node, scope)), - direction(readAttribute("direction", node, scope)), + direction(readAttribute("direction", node, scope, std::nullopt)), triggering_entities(triggering_entities), evaluations(triggering_entities.entity_refs.size(), Double::nan()) { @@ -69,8 +83,13 @@ struct RelativeSpeedCondition : private SimulatorCore::ConditionEvaluation { auto description = std::stringstream(); - description << triggering_entities.description() << "'s relative speed to given entity " - << entity_ref << " = "; + description << triggering_entities.description() << "'s relative "; + + if (direction) { + description << *direction << " "; + } + + description << "speed to given entity " << entity_ref << " = "; print_to(description, evaluations); @@ -84,8 +103,22 @@ struct RelativeSpeedCondition : private SimulatorCore::ConditionEvaluation evaluations.clear(); return asBoolean(triggering_entities.apply([this](auto && triggering_entity) { - [[deprecated]] auto evaluateRelativeSpeed = [](auto &&...) { return Double(); }; - evaluations.push_back(evaluateRelativeSpeed(triggering_entity, entity_ref)); + evaluations.push_back([this](auto && v) { + if (direction) { + switch (*direction) { + case DirectionalDimension::longitudinal: + return v.x; + case DirectionalDimension::lateral: + return v.y; + case DirectionalDimension::vertical: + return v.z; + default: + return math::geometry::norm(v); + } + } else { + return math::geometry::norm(v); + } + }(evaluateRelativeSpeed(triggering_entity, entity_ref))); return std::invoke(rule, evaluations.back(), value); })); } From d270cdcaf0d100b0949aff869756959029fa8c72 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 22 May 2024 16:58:51 +0900 Subject: [PATCH 05/25] Move entity existence check into `distance` from speceialized `distance` Signed-off-by: yamacir-kit --- .../syntax/relative_distance_condition.cpp | 385 +++++++----------- 1 file changed, 157 insertions(+), 228 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index 6309d00bbb3..56d28b7388d 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -66,31 +66,20 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x); - } else { - return Double::nan(); - } + return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x); } -/** - * @note This implementation differs from the OpenSCENARIO standard. See the section "6.4. Distances" in the OpenSCENARIO User Guide. - */ template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - return std::abs( - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x); - } else { - return Double::nan(); - } + /** + @note This implementation differs from the OpenSCENARIO standard. See the + section "6.4. Distances" in the OpenSCENARIO User Guide. + */ + return std::abs( + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x); } template <> @@ -98,35 +87,24 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y); - } else { - return Double::nan(); - } + return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y); } -/** - * @note This implementation differs from the OpenSCENARIO standard. See the section "6.4. Distances" in the OpenSCENARIO User Guide. - */ template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - return std::abs( - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y); - } else { - return Double::nan(); - } + /** + @note This implementation differs from the OpenSCENARIO standard. See the + section "6.4. Distances" in the OpenSCENARIO User Guide. + */ + return std::abs( + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y); } -// @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x,y,z) -static double hypot(const double x, const double y, const double z, const bool consider_z) +// @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x, y, z) +auto hypot(double x, double y, double z, bool consider_z) { return consider_z ? std::hypot(x, y, z) : std::hypot(x, y); } @@ -136,17 +114,11 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, true>(const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - return hypot( - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x, - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y, - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.z, - consider_z); - } else { - return Double::nan(); - } + return hypot( + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x, + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y, + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.z, + consider_z); } template <> @@ -154,16 +126,10 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, false>(const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - return hypot( - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x, - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y, - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.z, consider_z); - } else { - return Double::nan(); - } + return hypot( + makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x, + makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y, + makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.z, consider_z); } template <> @@ -171,27 +137,21 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(entity_ref).as().is_added and - global().entities->at(triggering_entity).as().is_added) { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == - longitudinal/lateral. The sign has been mainly used to determine the - front/back and left/right positional relationship (a negative value is - returned if the target entity is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's - OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this - behavior will be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref)) - .offset; - } else { - return Double::nan(); - } + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == longitudinal/lateral. + The sign has been mainly used to determine the front/back and left/right + positional relationship (a negative value is returned if the target entity + is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's OpenSCENARIO + Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this behavior will + be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref)) + .offset; } template <> @@ -199,27 +159,21 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(entity_ref).as().is_added and - global().entities->at(triggering_entity).as().is_added) { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == - longitudinal/lateral. The sign has been mainly used to determine the - front/back and left/right positional relationship (a negative value is - returned if the target entity is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's - OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this - behavior will be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) - .offset; - } else { - return Double::nan(); - } + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == longitudinal/lateral. + The sign has been mainly used to determine the front/back and left/right + positional relationship (a negative value is returned if the target entity + is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's OpenSCENARIO + Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this behavior will + be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) + .offset; } template <> @@ -227,27 +181,21 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == - longitudinal/lateral. The sign has been mainly used to determine the - front/back and left/right positional relationship (a negative value is - returned if the target entity is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's - OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this - behavior will be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref)) - .s; - } else { - return Double::nan(); - } + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == longitudinal/lateral. + The sign has been mainly used to determine the front/back and left/right + positional relationship (a negative value is returned if the target entity + is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's OpenSCENARIO + Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this behavior will + be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref)) + .s; } template <> @@ -255,27 +203,21 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == - longitudinal/lateral. The sign has been mainly used to determine the - front/back and left/right positional relationship (a negative value is - returned if the target entity is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's - OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this - behavior will be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) - .s; - } else { - return Double::nan(); - } + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == longitudinal/lateral. + The sign has been mainly used to determine the front/back and left/right + positional relationship (a negative value is returned if the target entity + is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's OpenSCENARIO + Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this behavior will + be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) + .s; } template <> @@ -283,16 +225,10 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, true>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(entity_ref).as().is_added and - global().entities->at(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, entity_ref, RoutingAlgorithm::shortest)) - .offset); - } else { - return Double::nan(); - } + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, entity_ref, RoutingAlgorithm::shortest)) + .offset); } template <> @@ -300,16 +236,10 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, false>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(entity_ref).as().is_added and - global().entities->at(triggering_entity).as().is_added) { - return std::abs( - static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref, RoutingAlgorithm::shortest)) - .offset); - } else { - return Double::nan(); - } + return std::abs( + static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref, RoutingAlgorithm::shortest)) + .offset); } template <> @@ -317,16 +247,10 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, true>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(entity_ref).as().is_added and - global().entities->at(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, entity_ref, RoutingAlgorithm::shortest)) - .s); - } else { - return Double::nan(); - } + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, entity_ref, RoutingAlgorithm::shortest)) + .s); } template <> @@ -334,64 +258,64 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, false>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(entity_ref).as().is_added and - global().entities->at(triggering_entity).as().is_added) { - return std::abs( - static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref, RoutingAlgorithm::shortest)) - .s); - } else { - return Double::nan(); - } + return std::abs( + static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref, RoutingAlgorithm::shortest)) + .s); } -#define SWITCH_COORDINATE_SYSTEM(FUNCTION, ...) \ - switch (coordinate_system) { \ - case CoordinateSystem::entity: \ - FUNCTION(__VA_ARGS__, CoordinateSystem::entity); \ - break; \ - case CoordinateSystem::lane: \ - FUNCTION(__VA_ARGS__, CoordinateSystem::lane); \ - break; \ - case CoordinateSystem::road: \ - FUNCTION(__VA_ARGS__, CoordinateSystem::road); \ - break; \ - case CoordinateSystem::trajectory: \ - FUNCTION(__VA_ARGS__, CoordinateSystem::trajectory); \ - break; \ +#define SWITCH_COORDINATE_SYSTEM(FUNCTION, ...) \ + switch (coordinate_system) { \ + case CoordinateSystem::entity: \ + FUNCTION(__VA_ARGS__, CoordinateSystem::entity); \ + break; \ + case CoordinateSystem::lane: \ + FUNCTION(__VA_ARGS__, CoordinateSystem::lane); \ + break; \ + case CoordinateSystem::road: \ + FUNCTION(__VA_ARGS__, CoordinateSystem::road); \ + break; \ + case CoordinateSystem::trajectory: \ + FUNCTION(__VA_ARGS__, CoordinateSystem::trajectory); \ + break; \ + default: \ + throw UNEXPECTED_ENUMERATION_VALUE_ASSIGNED(CoordinateSystem, coordinate_system); \ } -#define SWITCH_RELATIVE_DISTANCE_TYPE(FUNCTION, ...) \ - switch (relative_distance_type) { \ - case RelativeDistanceType::longitudinal: \ - FUNCTION(__VA_ARGS__, RelativeDistanceType::longitudinal); \ - break; \ - case RelativeDistanceType::lateral: \ - FUNCTION(__VA_ARGS__, RelativeDistanceType::lateral); \ - break; \ - case RelativeDistanceType::euclidianDistance: \ - FUNCTION(__VA_ARGS__, RelativeDistanceType::euclidianDistance); \ - break; \ +#define SWITCH_RELATIVE_DISTANCE_TYPE(FUNCTION, ...) \ + switch (relative_distance_type) { \ + case RelativeDistanceType::longitudinal: \ + FUNCTION(__VA_ARGS__, RelativeDistanceType::longitudinal); \ + break; \ + case RelativeDistanceType::lateral: \ + FUNCTION(__VA_ARGS__, RelativeDistanceType::lateral); \ + break; \ + case RelativeDistanceType::euclidianDistance: \ + FUNCTION(__VA_ARGS__, RelativeDistanceType::euclidianDistance); \ + break; \ + default: \ + throw UNEXPECTED_ENUMERATION_VALUE_ASSIGNED(RelativeDistanceType, relative_distance_type); \ } -#define SWITCH_ROUTING_ALGORITHM(FUNCTION, ...) \ - switch (routing_algorithm) { \ - case RoutingAlgorithm::assigned_route: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::assigned_route); \ - break; \ - case RoutingAlgorithm::fastest: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::fastest); \ - break; \ - case RoutingAlgorithm::least_intersections: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::least_intersections); \ - break; \ - case RoutingAlgorithm::shortest: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::shortest); \ - break; \ - case RoutingAlgorithm::undefined: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::undefined); \ - break; \ +#define SWITCH_ROUTING_ALGORITHM(FUNCTION, ...) \ + switch (routing_algorithm) { \ + case RoutingAlgorithm::assigned_route: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::assigned_route); \ + break; \ + case RoutingAlgorithm::fastest: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::fastest); \ + break; \ + case RoutingAlgorithm::least_intersections: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::least_intersections); \ + break; \ + case RoutingAlgorithm::shortest: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::shortest); \ + break; \ + case RoutingAlgorithm::undefined: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::undefined); \ + break; \ + default: \ + throw UNEXPECTED_ENUMERATION_VALUE_ASSIGNED(RoutingAlgorithm, routing_algorithm); \ } #define SWITCH_FREESPACE(FUNCTION, ...) \ @@ -401,9 +325,14 @@ auto RelativeDistanceCondition::distance< auto RelativeDistanceCondition::distance(const EntityRef & triggering_entity) -> double { - SWITCH_COORDINATE_SYSTEM( - SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); - return Double::nan(); + if ( + global().entities->at(triggering_entity).as().is_added and + global().entities->at(entity_ref).as().is_added) { + SWITCH_COORDINATE_SYSTEM( + SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); + } else { + return Double::nan(); + } } auto RelativeDistanceCondition::evaluate() -> Object From 3be8459641964857a2b9d89cc195957a2aed6023 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 22 May 2024 18:58:29 +0900 Subject: [PATCH 06/25] Update `RelativeDistanceCondition::distance` to static member function Signed-off-by: yamacir-kit --- .../syntax/relative_distance_condition.hpp | 36 +++++----- .../syntax/relative_distance_condition.cpp | 72 ++++++++++--------- 2 files changed, 55 insertions(+), 53 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp index 39926681b26..846eca5f40b 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp @@ -90,8 +90,6 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi std::vector results; // for description - const bool consider_z; - explicit RelativeDistanceCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &); auto description() const -> String; @@ -99,12 +97,14 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi template < CoordinateSystem::value_type, RelativeDistanceType::value_type, RoutingAlgorithm::value_type, Boolean::value_type> - auto distance(const EntityRef &) -> double + static auto distance(const EntityRef &, const EntityRef &) -> double { throw SyntaxError(__FILE__, ":", __LINE__); } - auto distance(const EntityRef &) -> double; + static auto distance( + const EntityRef &, const EntityRef &, const Entities &, CoordinateSystem, RelativeDistanceType, + RoutingAlgorithm, bool) -> double; auto evaluate() -> Object; }; @@ -113,20 +113,20 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi // cspell: ignore euclidian // clang-format off -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; // clang-format on } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index 56d28b7388d..4fe56f1e425 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -38,12 +38,7 @@ RelativeDistanceCondition::RelativeDistanceCondition( rule(readAttribute("rule", node, scope)), value(readAttribute("value", node, scope)), triggering_entities(triggering_entities), - results(triggering_entities.entity_refs.size(), Double::nan()), - consider_z([]() { - rclcpp::Node node{"get_parameter", "simulation"}; - node.declare_parameter("consider_pose_by_road_slope", false); - return node.get_parameter("consider_pose_by_road_slope").as_bool(); - }()) + results(triggering_entities.entity_refs.size(), Double::nan()) { } @@ -64,7 +59,7 @@ auto RelativeDistanceCondition::description() const -> String template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x); } @@ -72,7 +67,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { /** @note This implementation differs from the OpenSCENARIO standard. See the @@ -85,7 +80,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y); } @@ -93,7 +88,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { /** @note This implementation differs from the OpenSCENARIO standard. See the @@ -104,38 +99,40 @@ auto RelativeDistanceCondition::distance< } // @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x, y, z) -auto hypot(double x, double y, double z, bool consider_z) +auto hypot(double x, double y, double z) { + static auto consider_z = []() { + auto node = rclcpp::Node("get_parameter", "simulation"); + node.declare_parameter("consider_pose_by_road_slope", false); + return node.get_parameter("consider_pose_by_road_slope").as_bool(); + }(); + return consider_z ? std::hypot(x, y, z) : std::hypot(x, y); } template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, - true>(const EntityRef & triggering_entity) -> double + true>(const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { - return hypot( - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x, - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y, - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.z, - consider_z); + const auto relative_world = + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref); + return hypot(relative_world.position.x, relative_world.position.y, relative_world.position.z); } template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, - false>(const EntityRef & triggering_entity) -> double + false>(const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { - return hypot( - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x, - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y, - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.z, consider_z); + const auto relative_world = makeNativeRelativeWorldPosition(triggering_entity, entity_ref); + return hypot(relative_world.position.x, relative_world.position.y, relative_world.position.z); } template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { /* For historical reasons, signed distances are returned when @@ -157,7 +154,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { /* For historical reasons, signed distances are returned when @@ -179,7 +176,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { /* For historical reasons, signed distances are returned when @@ -201,7 +198,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { /* For historical reasons, signed distances are returned when @@ -223,7 +220,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { return std::abs(static_cast( makeNativeBoundingBoxRelativeLanePosition( @@ -234,7 +231,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { return std::abs( static_cast( @@ -245,7 +242,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { return std::abs(static_cast( makeNativeBoundingBoxRelativeLanePosition( @@ -256,7 +253,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { return std::abs( static_cast( @@ -321,13 +318,16 @@ auto RelativeDistanceCondition::distance< #define SWITCH_FREESPACE(FUNCTION, ...) \ return freespace ? FUNCTION(__VA_ARGS__, true) : FUNCTION(__VA_ARGS__, false) -#define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity) +#define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity, entity_ref) -auto RelativeDistanceCondition::distance(const EntityRef & triggering_entity) -> double +auto RelativeDistanceCondition::distance( + const EntityRef & triggering_entity, const EntityRef & entity_ref, const Entities & entities, + CoordinateSystem coordinate_system, RelativeDistanceType relative_distance_type, + RoutingAlgorithm routing_algorithm, bool freespace) -> double { if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { + entities.at(triggering_entity).as().is_added and + entities.at(entity_ref).as().is_added) { SWITCH_COORDINATE_SYSTEM( SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); } else { @@ -340,7 +340,9 @@ auto RelativeDistanceCondition::evaluate() -> Object results.clear(); return asBoolean(triggering_entities.apply([&](const auto & triggering_entity) { - results.push_back(distance(triggering_entity)); + results.push_back(distance( + triggering_entity, entity_ref, *global().entities, coordinate_system, relative_distance_type, + routing_algorithm, freespace)); return rule(static_cast(results.back()), value); })); } From 6535eebbe8d9a77a7aff6dc493b41ba994b5d0a1 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Mon, 3 Jun 2024 11:24:46 +0900 Subject: [PATCH 07/25] Add new static member function `RelativeSpeedCondition::evaluate` Signed-off-by: yamacir-kit --- .../include/geometry/vector3/norm.hpp | 1 + .../syntax/relative_distance_condition.hpp | 2 +- .../syntax/relative_speed_condition.hpp | 63 ++----------- .../syntax/time_to_collision_condition.hpp | 30 +++++- .../syntax/relative_distance_condition.cpp | 8 +- .../src/syntax/relative_speed_condition.cpp | 92 +++++++++++++++++++ 6 files changed, 133 insertions(+), 63 deletions(-) create mode 100644 openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp diff --git a/common/math/geometry/include/geometry/vector3/norm.hpp b/common/math/geometry/include/geometry/vector3/norm.hpp index 44fa57c9e62..6746c7ec7c6 100644 --- a/common/math/geometry/include/geometry/vector3/norm.hpp +++ b/common/math/geometry/include/geometry/vector3/norm.hpp @@ -15,6 +15,7 @@ #ifndef GEOMETRY__VECTOR3__NORM_HPP_ #define GEOMETRY__VECTOR3__NORM_HPP_ +#include #include namespace math diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp index 846eca5f40b..475f91ff739 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp @@ -103,7 +103,7 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi } static auto distance( - const EntityRef &, const EntityRef &, const Entities &, CoordinateSystem, RelativeDistanceType, + const EntityRef &, const EntityRef &, const Entities *, CoordinateSystem, RelativeDistanceType, RoutingAlgorithm, bool) -> double; auto evaluate() -> Object; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp index d535388c5dc..d42b50db0dd 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp @@ -15,11 +15,11 @@ #ifndef OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_SPEED_CONDITION_HPP_ #define OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_SPEED_CONDITION_HPP_ -#include #include #include #include -#include +#include +#include namespace openscenario_interpreter { @@ -41,7 +41,7 @@ inline namespace syntax */ -struct RelativeSpeedCondition : private SimulatorCore::ConditionEvaluation +struct RelativeSpeedCondition : private Scope, private SimulatorCore::ConditionEvaluation { /* Reference entity. @@ -68,60 +68,15 @@ struct RelativeSpeedCondition : private SimulatorCore::ConditionEvaluation std::vector evaluations; - explicit RelativeSpeedCondition( - const pugi::xml_node & node, Scope & scope, const TriggeringEntities & triggering_entities) - : entity_ref(readAttribute("entityRef", node, scope)), - rule(readAttribute("rule", node, scope)), - value(readAttribute("value", node, scope)), - direction(readAttribute("direction", node, scope, std::nullopt)), - triggering_entities(triggering_entities), - evaluations(triggering_entities.entity_refs.size(), Double::nan()) - { - } + explicit RelativeSpeedCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &); - auto description() const - { - auto description = std::stringstream(); + auto description() const -> String; - description << triggering_entities.description() << "'s relative "; + static auto evaluate( + const EntityRef &, const EntityRef &, const Entities *, + const std::optional &) -> double; - if (direction) { - description << *direction << " "; - } - - description << "speed to given entity " << entity_ref << " = "; - - print_to(description, evaluations); - - description << " " << rule << " " << value << "?"; - - return description.str(); - } - - auto evaluate() - { - evaluations.clear(); - - return asBoolean(triggering_entities.apply([this](auto && triggering_entity) { - evaluations.push_back([this](auto && v) { - if (direction) { - switch (*direction) { - case DirectionalDimension::longitudinal: - return v.x; - case DirectionalDimension::lateral: - return v.y; - case DirectionalDimension::vertical: - return v.z; - default: - return math::geometry::norm(v); - } - } else { - return math::geometry::norm(v); - } - }(evaluateRelativeSpeed(triggering_entity, entity_ref))); - return std::invoke(rule, evaluations.back(), value); - })); - } + auto evaluate() -> Object; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp index 2e8eee42cb2..39e7e776a1d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -17,6 +17,8 @@ #include #include +#include +#include #include #include @@ -59,7 +61,7 @@ inline namespace syntax */ -struct TimeToCollisionCondition : private SimulatorCore::ConditionEvaluation +struct TimeToCollisionCondition : private Scope, private SimulatorCore::ConditionEvaluation { const TimeToCollisionConditionTarget time_to_collision_condition_target; @@ -81,7 +83,8 @@ struct TimeToCollisionCondition : private SimulatorCore::ConditionEvaluation explicit TimeToCollisionCondition( const pugi::xml_node & node, Scope & scope, const TriggeringEntities & triggering_entities) - : time_to_collision_condition_target( + : Scope(scope), + time_to_collision_condition_target( readElement("TimeToCollisionConditionTarget", node, scope)), freespace(readAttribute("freespace", node, scope)), rule(readAttribute("rule", node, scope)), @@ -117,8 +120,27 @@ struct TimeToCollisionCondition : private SimulatorCore::ConditionEvaluation evaluations.clear(); return asBoolean(triggering_entities.apply([this](auto && triggering_entity) { - [[deprecated]] auto evaluateTimeToCollision = [](auto &&...) { return Double(); }; - evaluations.push_back(evaluateTimeToCollision(triggering_entity, "TODO")); + [[deprecated]] auto evaluateTimeToCollision = + [this]( + const EntityRef & triggering_entity, + const TimeToCollisionConditionTarget & time_to_collision_condition_target) { + if (time_to_collision_condition_target.is()) { + std::cerr << "RELATIVE DISTANCE = " + << RelativeDistanceCondition::distance( + triggering_entity, time_to_collision_condition_target.as(), + global().entities, coordinate_system, relative_distance_type, + routing_algorithm, freespace) + << ", " + << "RELATIVE SPEED = " + << RelativeSpeedCondition::evaluate( + triggering_entity, time_to_collision_condition_target.as(), + global().entities, std::nullopt) + << std::endl; + } + return Double(); + }; + evaluations.push_back( + evaluateTimeToCollision(triggering_entity, time_to_collision_condition_target)); return std::invoke(rule, evaluations.back(), value); })); } diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index 8740ef9761c..349ebae69ae 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -328,13 +328,13 @@ auto RelativeDistanceCondition::distance< #define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity, entity_ref) auto RelativeDistanceCondition::distance( - const EntityRef & triggering_entity, const EntityRef & entity_ref, const Entities & entities, + const EntityRef & triggering_entity, const EntityRef & entity_ref, const Entities * entities, CoordinateSystem coordinate_system, RelativeDistanceType relative_distance_type, RoutingAlgorithm routing_algorithm, bool freespace) -> double { if ( - entities.at(triggering_entity).as().is_added and - entities.at(entity_ref).as().is_added) { + entities->at(triggering_entity).as().is_added and + entities->at(entity_ref).as().is_added) { SWITCH_COORDINATE_SYSTEM( SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); } else { @@ -348,7 +348,7 @@ auto RelativeDistanceCondition::evaluate() -> Object return asBoolean(triggering_entities.apply([&](const auto & triggering_entity) { results.push_back(distance( - triggering_entity, entity_ref, *global().entities, coordinate_system, relative_distance_type, + triggering_entity, entity_ref, global().entities, coordinate_system, relative_distance_type, routing_algorithm, freespace)); return rule(static_cast(results.back()), value); })); diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp new file mode 100644 index 00000000000..0e7d30bd03f --- /dev/null +++ b/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp @@ -0,0 +1,92 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include +#include + +namespace openscenario_interpreter +{ +inline namespace syntax +{ +RelativeSpeedCondition::RelativeSpeedCondition( + const pugi::xml_node & node, Scope & scope, const TriggeringEntities & triggering_entities) +: Scope(scope), + entity_ref(readAttribute("entityRef", node, scope)), + rule(readAttribute("rule", node, scope)), + value(readAttribute("value", node, scope)), + direction(readAttribute("direction", node, scope, std::nullopt)), + triggering_entities(triggering_entities), + evaluations(triggering_entities.entity_refs.size(), Double::nan()) +{ +} + +auto RelativeSpeedCondition::description() const -> String +{ + auto description = std::stringstream(); + + description << triggering_entities.description() << "'s relative "; + + if (direction) { + description << *direction << " "; + } + + description << "speed to given entity " << entity_ref << " = "; + + print_to(description, evaluations); + + description << " " << rule << " " << value << "?"; + + return description.str(); +} + +auto RelativeSpeedCondition::evaluate( + const EntityRef & triggering_entity, const EntityRef & entity_ref, const Entities * entities, + const std::optional & direction) -> double +{ + if ( + entities->at(triggering_entity).as().is_added and + entities->at(entity_ref).as().is_added) { + if (const auto v = evaluateRelativeSpeed(triggering_entity, entity_ref); direction) { + switch (*direction) { + case DirectionalDimension::longitudinal: + return v.x; + case DirectionalDimension::lateral: + return v.y; + case DirectionalDimension::vertical: + return v.z; + default: + return math::geometry::norm(v); + } + } else { + return math::geometry::norm(v); + } + } else { + return Double::nan(); + } +} + +auto RelativeSpeedCondition::evaluate() -> Object +{ + evaluations.clear(); + + return asBoolean(triggering_entities.apply([this](auto && triggering_entity) { + evaluations.push_back(evaluate(triggering_entity, entity_ref, global().entities, direction)); + return std::invoke(rule, evaluations.back(), value); + })); +} +} // namespace syntax +} // namespace openscenario_interpreter From be16d09e3ed0e6865a8ac8cd42a638edd84c5188 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 26 Jun 2024 16:44:01 +0900 Subject: [PATCH 08/25] Remove data member `DistanceCondition::consider_z` Signed-off-by: yamacir-kit --- .../syntax/distance_condition.hpp | 36 +++++----- .../src/syntax/distance_condition.cpp | 69 +++++++++---------- 2 files changed, 49 insertions(+), 56 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp index 61ea2db6345..f64e250326e 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp @@ -107,18 +107,18 @@ struct DistanceCondition : private Scope, private SimulatorCore::ConditionEvalua std::vector results; // for description - const bool consider_z; - explicit DistanceCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &); auto description() const -> std::string; - auto distance(const EntityRef &) const -> double; + // TODO STATIC + auto distance(const EntityRef &) -> double; template < CoordinateSystem::value_type, RelativeDistanceType::value_type, RoutingAlgorithm::value_type, Boolean::value_type> - auto distance(const EntityRef &) const -> double + // TODO STATIC + auto distance(const EntityRef &) -> double { throw SyntaxError(__FILE__, ":", __LINE__); } @@ -130,20 +130,20 @@ struct DistanceCondition : private Scope, private SimulatorCore::ConditionEvalua // cspell: ignore euclidian // clang-format off -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; -template <> auto DistanceCondition::distance(const EntityRef &) const -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &) -> double; // clang-format on } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp index 4e817bb7286..f759f485c79 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp @@ -46,12 +46,7 @@ DistanceCondition::DistanceCondition( value(readAttribute("value", node, scope)), position(readElement("Position", node, scope)), triggering_entities(triggering_entities), - results(triggering_entities.entity_refs.size(), Double::nan()), - consider_z([]() { - rclcpp::Node node{"get_parameter", "simulation"}; - node.declare_parameter("consider_pose_by_road_slope", false); - return node.get_parameter("consider_pose_by_road_slope").as_bool(); - }()) + results(triggering_entities.entity_refs.size(), Double::nan()) { std::set supported = { RoutingAlgorithm::value_type::shortest, RoutingAlgorithm::value_type::undefined}; @@ -127,7 +122,7 @@ auto DistanceCondition::description() const -> std::string #define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity) -auto DistanceCondition::distance(const EntityRef & triggering_entity) const -> double +auto DistanceCondition::distance(const EntityRef & triggering_entity) -> double { SWITCH_COORDINATE_SYSTEM( SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); @@ -135,15 +130,21 @@ auto DistanceCondition::distance(const EntityRef & triggering_entity) const -> d } // @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x,y,z) -static double hypot(const double x, const double y, const double z, const bool consider_z) +static auto hypot(const double x, const double y, const double z) { + static auto consider_z = []() { + auto node = rclcpp::Node("get_parameter", "simulation"); + node.declare_parameter("consider_pose_by_road_slope", false); + return node.get_parameter("consider_pose_by_road_slope").as_bool(); + }(); + return consider_z ? std::hypot(x, y, z) : std::hypot(x, y); } template <> auto DistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, - false>(const EntityRef & triggering_entity) const -> double + false>(const EntityRef & triggering_entity) -> double { return apply( overload( @@ -151,29 +152,25 @@ auto DistanceCondition::distance< const auto relative_world = makeNativeRelativeWorldPosition( triggering_entity, static_cast(position)); return hypot( - relative_world.position.x, relative_world.position.y, relative_world.position.z, - consider_z); + relative_world.position.x, relative_world.position.y, relative_world.position.z); }, [&](const RelativeWorldPosition & position) { const auto relative_world = makeNativeRelativeWorldPosition( triggering_entity, static_cast(position)); return hypot( - relative_world.position.x, relative_world.position.y, relative_world.position.z, - consider_z); + relative_world.position.x, relative_world.position.y, relative_world.position.z); }, [&](const RelativeObjectPosition & position) { const auto relative_world = makeNativeRelativeWorldPosition( triggering_entity, static_cast(position)); return hypot( - relative_world.position.x, relative_world.position.y, relative_world.position.z, - consider_z); + relative_world.position.x, relative_world.position.y, relative_world.position.z); }, [&](const LanePosition & position) { const auto relative_world = makeNativeRelativeWorldPosition( triggering_entity, static_cast(position)); return hypot( - relative_world.position.x, relative_world.position.y, relative_world.position.z, - consider_z); + relative_world.position.x, relative_world.position.y, relative_world.position.z); }), position); } @@ -181,7 +178,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, - true>(const EntityRef & triggering_entity) const -> double + true>(const EntityRef & triggering_entity) -> double { return apply( overload( @@ -189,29 +186,25 @@ auto DistanceCondition::distance< const auto relative_world = makeNativeBoundingBoxRelativeWorldPosition( triggering_entity, static_cast(position)); return hypot( - relative_world.position.x, relative_world.position.y, relative_world.position.z, - consider_z); + relative_world.position.x, relative_world.position.y, relative_world.position.z); }, [&](const RelativeWorldPosition & position) { const auto relative_world = makeNativeBoundingBoxRelativeWorldPosition( triggering_entity, static_cast(position)); return hypot( - relative_world.position.x, relative_world.position.y, relative_world.position.z, - consider_z); + relative_world.position.x, relative_world.position.y, relative_world.position.z); }, [&](const RelativeObjectPosition & position) { const auto relative_world = makeNativeBoundingBoxRelativeWorldPosition( triggering_entity, static_cast(position)); return hypot( - relative_world.position.x, relative_world.position.y, relative_world.position.z, - consider_z); + relative_world.position.x, relative_world.position.y, relative_world.position.z); }, [&](const LanePosition & position) { const auto relative_world = makeNativeBoundingBoxRelativeWorldPosition( triggering_entity, static_cast(position)); return hypot( - relative_world.position.x, relative_world.position.y, relative_world.position.z, - consider_z); + relative_world.position.x, relative_world.position.y, relative_world.position.z); }), position); } @@ -219,7 +212,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) const -> double + const EntityRef & triggering_entity) -> double { return apply( overload( @@ -249,7 +242,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) const -> double + const EntityRef & triggering_entity) -> double { return apply( overload( @@ -279,7 +272,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) const -> double + const EntityRef & triggering_entity) -> double { return apply( overload( @@ -309,7 +302,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) const -> double + const EntityRef & triggering_entity) -> double { return apply( overload( @@ -339,7 +332,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) const -> double + const EntityRef & triggering_entity) -> double { return apply( overload( @@ -388,7 +381,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) const -> double + const EntityRef & triggering_entity) -> double { return apply( overload( @@ -437,7 +430,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) const -> double + const EntityRef & triggering_entity) -> double { return apply( overload( @@ -486,7 +479,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) const -> double + const EntityRef & triggering_entity) -> double { return apply( overload( @@ -535,7 +528,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, false>( - const EntityRef & triggering_entity) const -> double + const EntityRef & triggering_entity) -> double { return apply( overload( @@ -588,7 +581,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, true>( - const EntityRef & triggering_entity) const -> double + const EntityRef & triggering_entity) -> double { return apply( overload( @@ -641,7 +634,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, false>( - const EntityRef & triggering_entity) const -> double + const EntityRef & triggering_entity) -> double { return apply( overload( @@ -694,7 +687,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, true>( - const EntityRef & triggering_entity) const -> double + const EntityRef & triggering_entity) -> double { return apply( overload( From 77a1b31e289734ae59baeff140fc62b3c55d4acc Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 26 Jun 2024 16:57:36 +0900 Subject: [PATCH 09/25] Add `const Position &` to the argument of `DistanceCondition::distance` Signed-off-by: yamacir-kit --- .../syntax/distance_condition.hpp | 33 +++++++++-------- .../src/syntax/distance_condition.cpp | 35 ++++++++++--------- 2 files changed, 34 insertions(+), 34 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp index f64e250326e..6ace25ce376 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp @@ -112,13 +112,12 @@ struct DistanceCondition : private Scope, private SimulatorCore::ConditionEvalua auto description() const -> std::string; // TODO STATIC - auto distance(const EntityRef &) -> double; + auto distance(const EntityRef &, const Position &) -> double; template < CoordinateSystem::value_type, RelativeDistanceType::value_type, RoutingAlgorithm::value_type, Boolean::value_type> - // TODO STATIC - auto distance(const EntityRef &) -> double + auto distance(const EntityRef &, const Position &) -> double { throw SyntaxError(__FILE__, ":", __LINE__); } @@ -130,20 +129,20 @@ struct DistanceCondition : private Scope, private SimulatorCore::ConditionEvalua // cspell: ignore euclidian // clang-format off -template <> auto DistanceCondition::distance(const EntityRef &) -> double; -template <> auto DistanceCondition::distance(const EntityRef &) -> double; -template <> auto DistanceCondition::distance(const EntityRef &) -> double; -template <> auto DistanceCondition::distance(const EntityRef &) -> double; -template <> auto DistanceCondition::distance(const EntityRef &) -> double; -template <> auto DistanceCondition::distance(const EntityRef &) -> double; -template <> auto DistanceCondition::distance(const EntityRef &) -> double; -template <> auto DistanceCondition::distance(const EntityRef &) -> double; -template <> auto DistanceCondition::distance(const EntityRef &) -> double; -template <> auto DistanceCondition::distance(const EntityRef &) -> double; -template <> auto DistanceCondition::distance(const EntityRef &) -> double; -template <> auto DistanceCondition::distance(const EntityRef &) -> double; -template <> auto DistanceCondition::distance(const EntityRef &) -> double; -template <> auto DistanceCondition::distance(const EntityRef &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; +template <> auto DistanceCondition::distance(const EntityRef &, const Position &) -> double; // clang-format on } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp index f759f485c79..e59f6cb38d7 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp @@ -120,9 +120,10 @@ auto DistanceCondition::description() const -> std::string #define SWITCH_FREESPACE(FUNCTION, ...) \ return freespace ? FUNCTION(__VA_ARGS__, true) : FUNCTION(__VA_ARGS__, false) -#define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity) +#define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity, position) -auto DistanceCondition::distance(const EntityRef & triggering_entity) -> double +auto DistanceCondition::distance(const EntityRef & triggering_entity, const Position & position) + -> double { SWITCH_COORDINATE_SYSTEM( SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); @@ -144,7 +145,7 @@ static auto hypot(const double x, const double y, const double z) template <> auto DistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, - false>(const EntityRef & triggering_entity) -> double + false>(const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -178,7 +179,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, - true>(const EntityRef & triggering_entity) -> double + true>(const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -212,7 +213,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -242,7 +243,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -272,7 +273,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -302,7 +303,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -332,7 +333,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -381,7 +382,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -430,7 +431,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -479,7 +480,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -528,7 +529,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -581,7 +582,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -634,7 +635,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -687,7 +688,7 @@ auto DistanceCondition::distance< template <> auto DistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const Position & position) -> double { return apply( overload( @@ -742,7 +743,7 @@ auto DistanceCondition::evaluate() -> Object results.clear(); return asBoolean(triggering_entities.apply([&](auto && triggering_entity) { - results.push_back(distance(triggering_entity)); + results.push_back(distance(triggering_entity, position)); return rule(static_cast(results.back()), value); })); } From 9b13ccd31853c522ce6bf87b80aeceb97f110820 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 26 Jun 2024 17:20:03 +0900 Subject: [PATCH 10/25] Update member function `CoordinateSystem::distance` to be static member Signed-off-by: yamacir-kit --- .../syntax/distance_condition.hpp | 2 +- .../src/syntax/distance_condition.cpp | 409 ++++++------------ 2 files changed, 143 insertions(+), 268 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp index 6ace25ce376..4068c498995 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp @@ -117,7 +117,7 @@ struct DistanceCondition : private Scope, private SimulatorCore::ConditionEvalua template < CoordinateSystem::value_type, RelativeDistanceType::value_type, RoutingAlgorithm::value_type, Boolean::value_type> - auto distance(const EntityRef &, const Position &) -> double + static auto distance(const EntityRef &, const Position &) -> double { throw SyntaxError(__FILE__, ":", __LINE__); } diff --git a/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp index e59f6cb38d7..5a73c536e7f 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp @@ -125,9 +125,12 @@ auto DistanceCondition::description() const -> std::string auto DistanceCondition::distance(const EntityRef & triggering_entity, const Position & position) -> double { - SWITCH_COORDINATE_SYSTEM( - SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); - return Double::nan(); + if (global().entities->ref(triggering_entity).as().is_added) { + SWITCH_COORDINATE_SYSTEM( + SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); + } else { + return Double::nan(); + } } // @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x,y,z) @@ -338,43 +341,27 @@ auto DistanceCondition::distance< return apply( overload( [&](const WorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return static_cast( - makeNativeRelativeLanePosition( - triggering_entity, static_cast(position))) - .offset; - } else { - return std::numeric_limits::quiet_NaN(); - } + return static_cast( + makeNativeRelativeLanePosition( + triggering_entity, static_cast(position))) + .offset; }, [&](const RelativeWorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return static_cast( - makeNativeRelativeLanePosition( - triggering_entity, static_cast(position))) - .offset; - } else { - return std::numeric_limits::quiet_NaN(); - } + return static_cast( + makeNativeRelativeLanePosition( + triggering_entity, static_cast(position))) + .offset; }, [&](const RelativeObjectPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return makeNativeRelativeLanePosition( - triggering_entity, static_cast(position)) - .offset; - } else { - return std::numeric_limits::quiet_NaN(); - } + return makeNativeRelativeLanePosition( + triggering_entity, static_cast(position)) + .offset; }, [&](const LanePosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return static_cast( - makeNativeRelativeLanePosition( - triggering_entity, static_cast(position))) - .offset; - } else { - return std::numeric_limits::quiet_NaN(); - } + return static_cast( + makeNativeRelativeLanePosition( + triggering_entity, static_cast(position))) + .offset; }), position); } @@ -387,43 +374,27 @@ auto DistanceCondition::distance< return apply( overload( [&](const WorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position))) - .offset; - } else { - return std::numeric_limits::quiet_NaN(); - } + return static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position))) + .offset; }, [&](const RelativeWorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position))) - .offset; - } else { - return std::numeric_limits::quiet_NaN(); - } + return static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position))) + .offset; }, [&](const RelativeObjectPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position)) - .offset; - } else { - return std::numeric_limits::quiet_NaN(); - } + return makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position)) + .offset; }, [&](const LanePosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position))) - .offset; - } else { - return std::numeric_limits::quiet_NaN(); - } + return static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position))) + .offset; }), position); } @@ -436,43 +407,27 @@ auto DistanceCondition::distance< return apply( overload( [&](const WorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return static_cast( - makeNativeRelativeLanePosition( - triggering_entity, static_cast(position))) - .s; - } else { - return std::numeric_limits::quiet_NaN(); - } + return static_cast( + makeNativeRelativeLanePosition( + triggering_entity, static_cast(position))) + .s; }, [&](const RelativeWorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return static_cast( - makeNativeRelativeLanePosition( - triggering_entity, static_cast(position))) - .s; - } else { - return std::numeric_limits::quiet_NaN(); - } + return static_cast( + makeNativeRelativeLanePosition( + triggering_entity, static_cast(position))) + .s; }, [&](const RelativeObjectPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return makeNativeRelativeLanePosition( - triggering_entity, static_cast(position)) - .s; - } else { - return std::numeric_limits::quiet_NaN(); - } + return makeNativeRelativeLanePosition( + triggering_entity, static_cast(position)) + .s; }, [&](const LanePosition & position) { - if (global().entities->ref(triggering_entity).template as().is_added) { - return static_cast( - makeNativeRelativeLanePosition( - triggering_entity, static_cast(position))) - .s; - } else { - return std::numeric_limits::quiet_NaN(); - } + return static_cast( + makeNativeRelativeLanePosition( + triggering_entity, static_cast(position))) + .s; }), position); } @@ -485,43 +440,27 @@ auto DistanceCondition::distance< return apply( overload( [&](const WorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position))) - .s; - } else { - return std::numeric_limits::quiet_NaN(); - } + return static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position))) + .s; }, [&](const RelativeWorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position))) - .s; - } else { - return std::numeric_limits::quiet_NaN(); - } + return static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position))) + .s; }, [&](const RelativeObjectPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position)) - .s; - } else { - return std::numeric_limits::quiet_NaN(); - } + return makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position)) + .s; }, [&](const LanePosition & position) { - if (global().entities->ref(triggering_entity).template as().is_added) { - return static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position))) - .s; - } else { - return std::numeric_limits::quiet_NaN(); - } + return static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position))) + .s; }), position); } @@ -534,47 +473,31 @@ auto DistanceCondition::distance< return apply( overload( [&](const WorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest)) - .offset); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(static_cast( + makeNativeRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest)) + .offset); }, [&](const RelativeWorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest)) - .offset); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(static_cast( + makeNativeRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest)) + .offset); }, [&](const RelativeObjectPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(makeNativeRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest) - .offset); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(makeNativeRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest) + .offset); }, [&](const LanePosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest)) - .offset); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(static_cast( + makeNativeRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest)) + .offset); }), position); } @@ -587,47 +510,31 @@ auto DistanceCondition::distance< return apply( overload( [&](const WorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest)) - .offset); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest)) + .offset); }, [&](const RelativeWorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest)) - .offset); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest)) + .offset); }, [&](const RelativeObjectPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest) - .offset); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest) + .offset); }, [&](const LanePosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest)) - .offset); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest)) + .offset); }), position); } @@ -640,47 +547,31 @@ auto DistanceCondition::distance< return apply( overload( [&](const WorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest)) - .s); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(static_cast( + makeNativeRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest)) + .s); }, [&](const RelativeWorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest)) - .s); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(static_cast( + makeNativeRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest)) + .s); }, [&](const RelativeObjectPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(makeNativeRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest) - .s); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(makeNativeRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest) + .s); }, [&](const LanePosition & position) { - if (global().entities->ref(triggering_entity).template as().is_added) { - return std::abs(static_cast( - makeNativeRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest)) - .s); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(static_cast( + makeNativeRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest)) + .s); }), position); } @@ -693,47 +584,31 @@ auto DistanceCondition::distance< return apply( overload( [&](const WorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest)) - .s); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest)) + .s); }, [&](const RelativeWorldPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest)) - .s); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest)) + .s); }, [&](const RelativeObjectPosition & position) { - if (global().entities->ref(triggering_entity).as().is_added) { - return std::abs(makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest) - .s); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest) + .s); }, [&](const LanePosition & position) { - if (global().entities->ref(triggering_entity).template as().is_added) { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, static_cast(position), - RoutingAlgorithm::shortest)) - .s); - } else { - return std::numeric_limits::quiet_NaN(); - } + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, static_cast(position), + RoutingAlgorithm::shortest)) + .s); }), position); } From f95eccb3711f4a036b9f67d8de25a901c3aa5b0f Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 27 Jun 2024 14:33:59 +0900 Subject: [PATCH 11/25] Rename `(Relative)?DistanceCondition::distance` to `evaluate` Signed-off-by: yamacir-kit --- .../syntax/distance_condition.hpp | 7 ++++--- .../syntax/relative_distance_condition.hpp | 2 +- .../syntax/speed_condition.hpp | 4 +++- .../syntax/time_to_collision_condition.hpp | 16 +++++++++++++--- .../src/syntax/distance_condition.cpp | 12 ++++++++---- .../src/syntax/relative_distance_condition.cpp | 4 ++-- .../src/syntax/speed_condition.cpp | 18 ++++++++++++++++-- 7 files changed, 47 insertions(+), 16 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp index 4068c498995..453a31fed35 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp @@ -111,9 +111,6 @@ struct DistanceCondition : private Scope, private SimulatorCore::ConditionEvalua auto description() const -> std::string; - // TODO STATIC - auto distance(const EntityRef &, const Position &) -> double; - template < CoordinateSystem::value_type, RelativeDistanceType::value_type, RoutingAlgorithm::value_type, Boolean::value_type> @@ -122,6 +119,10 @@ struct DistanceCondition : private Scope, private SimulatorCore::ConditionEvalua throw SyntaxError(__FILE__, ":", __LINE__); } + static auto evaluate( + const EntityRef &, const Position &, const Entities *, CoordinateSystem, RelativeDistanceType, + RoutingAlgorithm, bool) -> double; + auto evaluate() -> Object; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp index 475f91ff739..bf09beca6d2 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp @@ -102,7 +102,7 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi throw SyntaxError(__FILE__, ":", __LINE__); } - static auto distance( + static auto evaluate( const EntityRef &, const EntityRef &, const Entities *, CoordinateSystem, RelativeDistanceType, RoutingAlgorithm, bool) -> double; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp index 29d0be6eb99..9e3398a4ecb 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp @@ -37,7 +37,7 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct SpeedCondition : private SimulatorCore::ConditionEvaluation +struct SpeedCondition : private Scope, private SimulatorCore::ConditionEvaluation { const Double value; @@ -51,6 +51,8 @@ struct SpeedCondition : private SimulatorCore::ConditionEvaluation auto description() const -> String; + static auto evaluate(const EntityRef &, const Entities *) -> double; + auto evaluate() -> Object; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp index 39e7e776a1d..23140651a67 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -17,8 +17,10 @@ #include #include +#include #include #include +#include #include #include @@ -126,16 +128,24 @@ struct TimeToCollisionCondition : private Scope, private SimulatorCore::Conditio const TimeToCollisionConditionTarget & time_to_collision_condition_target) { if (time_to_collision_condition_target.is()) { std::cerr << "RELATIVE DISTANCE = " - << RelativeDistanceCondition::distance( + << RelativeDistanceCondition::evaluate( triggering_entity, time_to_collision_condition_target.as(), global().entities, coordinate_system, relative_distance_type, routing_algorithm, freespace) - << ", " - << "RELATIVE SPEED = " + << ", RELATIVE SPEED = " << RelativeSpeedCondition::evaluate( triggering_entity, time_to_collision_condition_target.as(), global().entities, std::nullopt) << std::endl; + } else { + std::cerr << "DISTANCE = " + << DistanceCondition::evaluate( + triggering_entity, time_to_collision_condition_target.as(), + global().entities, coordinate_system, relative_distance_type, + routing_algorithm, freespace) + << ", RELATIVE SPEED = " + << SpeedCondition::evaluate(triggering_entity, global().entities) + << std::endl; } return Double(); }; diff --git a/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp index 5a73c536e7f..4621497b6f0 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp @@ -122,10 +122,12 @@ auto DistanceCondition::description() const -> std::string #define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity, position) -auto DistanceCondition::distance(const EntityRef & triggering_entity, const Position & position) - -> double +auto DistanceCondition::evaluate( + const EntityRef & triggering_entity, const Position & position, const Entities * entities, + CoordinateSystem coordinate_system, RelativeDistanceType relative_distance_type, + RoutingAlgorithm routing_algorithm, bool freespace) -> double { - if (global().entities->ref(triggering_entity).as().is_added) { + if (entities->ref(triggering_entity).as().is_added) { SWITCH_COORDINATE_SYSTEM( SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); } else { @@ -618,7 +620,9 @@ auto DistanceCondition::evaluate() -> Object results.clear(); return asBoolean(triggering_entities.apply([&](auto && triggering_entity) { - results.push_back(distance(triggering_entity, position)); + results.push_back(evaluate( + triggering_entity, position, global().entities, coordinate_system, relative_distance_type, + routing_algorithm, freespace)); return rule(static_cast(results.back()), value); })); } diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index 349ebae69ae..36203a6479b 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -327,7 +327,7 @@ auto RelativeDistanceCondition::distance< #define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity, entity_ref) -auto RelativeDistanceCondition::distance( +auto RelativeDistanceCondition::evaluate( const EntityRef & triggering_entity, const EntityRef & entity_ref, const Entities * entities, CoordinateSystem coordinate_system, RelativeDistanceType relative_distance_type, RoutingAlgorithm routing_algorithm, bool freespace) -> double @@ -347,7 +347,7 @@ auto RelativeDistanceCondition::evaluate() -> Object results.clear(); return asBoolean(triggering_entities.apply([&](const auto & triggering_entity) { - results.push_back(distance( + results.push_back(evaluate( triggering_entity, entity_ref, global().entities, coordinate_system, relative_distance_type, routing_algorithm, freespace)); return rule(static_cast(results.back()), value); diff --git a/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp index 95f4f9b2497..4c4c34e131f 100644 --- a/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp @@ -13,7 +13,10 @@ // limitations under the License. #include +#include #include +#include +#include #include #include @@ -23,7 +26,8 @@ inline namespace syntax { SpeedCondition::SpeedCondition( const pugi::xml_node & node, Scope & scope, const TriggeringEntities & triggering_entities) -: value(readAttribute("value", node, scope)), +: Scope(scope), + value(readAttribute("value", node, scope)), compare(readAttribute("rule", node, scope)), triggering_entities(triggering_entities), results(triggering_entities.entity_refs.size(), Double::nan()) @@ -43,12 +47,22 @@ auto SpeedCondition::description() const -> String return description.str(); } +auto SpeedCondition::evaluate(const EntityRef & triggering_entity, const Entities * entities) + -> double +{ + if (entities->ref(triggering_entity).as().is_added) { + return evaluateSpeed(triggering_entity); + } else { + return Double::nan(); + } +} + auto SpeedCondition::evaluate() -> Object { results.clear(); return asBoolean(triggering_entities.apply([&](auto && triggering_entity) { - results.push_back(evaluateSpeed(triggering_entity)); + results.push_back(evaluate(triggering_entity, global().entities)); return compare(results.back(), value); })); } From 26e5a413f1ee5d8751abc3a281b06ab470b3703e Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 5 Jul 2024 16:14:32 +0900 Subject: [PATCH 12/25] Add support for `DirectionalDimension` to `SpeedCondition` Signed-off-by: yamacir-kit --- .../simulator_core.hpp | 2 +- .../syntax/speed_action.hpp | 3 +- .../syntax/speed_condition.hpp | 46 +++++++++++++------ .../syntax/speed_profile_action.hpp | 3 +- .../src/syntax/speed_action.cpp | 14 ++++-- .../src/syntax/speed_condition.cpp | 38 ++++++++++----- .../src/syntax/speed_profile_action.cpp | 7 ++- 7 files changed, 76 insertions(+), 37 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index ee5ee67895f..f6417f82168 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -507,7 +507,7 @@ class SimulatorCore template static auto evaluateSpeed(Ts &&... xs) { - return core->getCurrentTwist(std::forward(xs)...).linear.x; + return core->getCurrentTwist(std::forward(xs)...).linear; } template diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_action.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_action.hpp index 54f7eded7eb..0eeb69dff4d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_action.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_action.hpp @@ -38,8 +38,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ struct SpeedAction : private Scope, // NOTE: Required for access to actors - private SimulatorCore::ActionApplication, - private SimulatorCore::ConditionEvaluation + private SimulatorCore::ActionApplication { const TransitionDynamics speed_action_dynamics; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp index 9e3398a4ecb..7a776f2c0c2 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp @@ -17,6 +17,7 @@ #include #include +#include #include #include #include @@ -26,32 +27,49 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- SpeedCondition --------------------------------------------------------- - * - * Compares a triggering entity's/entities' speed to a target speed. The - * logical operator for the comparison is given by the rule attribute. - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + SpeedCondition (OpenSCENARIO XML 1.3) + + Compares a triggering entity's/entities' speed to a target speed. + The logical operator for the comparison is given by the rule + attribute. If direction is used, only the projection to that + direction is used in the comparison. + + + + + + +*/ struct SpeedCondition : private Scope, private SimulatorCore::ConditionEvaluation { + /* + The operator (less, greater, equal). + */ + const Rule rule; + + /* + Speed value of the speed condition. Unit: [m/s]. + */ const Double value; - const Rule compare; + /* + Direction of the speed (if not given, the total speed is + considered). + */ + const std::optional direction; const TriggeringEntities triggering_entities; - std::vector results; // for description + std::vector evaluations; // for description explicit SpeedCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &); auto description() const -> String; - static auto evaluate(const EntityRef &, const Entities *) -> double; + static auto evaluate( + const EntityRef &, const Entities *, const std::optional & = std::nullopt) + -> double; auto evaluate() -> Object; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_profile_action.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_profile_action.hpp index 2fea3279574..b6ce60f977b 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_profile_action.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_profile_action.hpp @@ -40,8 +40,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ struct SpeedProfileAction : private Scope, // NOTE: Required for access to actors - private SimulatorCore::ActionApplication, - private SimulatorCore::ConditionEvaluation + private SimulatorCore::ActionApplication { /* Reference entity. If set, the speed values will be interpreted as relative diff --git a/openscenario/openscenario_interpreter/src/syntax/speed_action.cpp b/openscenario/openscenario_interpreter/src/syntax/speed_action.cpp index e72523eb949..c3a10522d76 100644 --- a/openscenario/openscenario_interpreter/src/syntax/speed_action.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/speed_action.cpp @@ -16,6 +16,7 @@ #include #include #include +#include namespace openscenario_interpreter { @@ -45,19 +46,22 @@ auto SpeedAction::accomplished() -> bool auto check = [this](auto && actor) { if (speed_action_target.is()) { return equal_to()( - speed_action_target.as().value, evaluateSpeed(actor)); + speed_action_target.as().value, + SpeedCondition::evaluate(actor, global().entities)); } else { switch (speed_action_target.as().speed_target_value_type) { case SpeedTargetValueType::delta: return equal_to()( - evaluateSpeed(speed_action_target.as().entity_ref) + + SpeedCondition::evaluate( + speed_action_target.as().entity_ref, global().entities) + speed_action_target.as().value, - evaluateSpeed(actor)); + SpeedCondition::evaluate(actor, global().entities)); case SpeedTargetValueType::factor: return equal_to()( - evaluateSpeed(speed_action_target.as().entity_ref) * + SpeedCondition::evaluate( + speed_action_target.as().entity_ref, global().entities) * speed_action_target.as().value, - evaluateSpeed(actor)); + SpeedCondition::evaluate(actor, global().entities)); default: return false; } diff --git a/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp index 4c4c34e131f..1e8ebcdf228 100644 --- a/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include #include @@ -27,10 +28,11 @@ inline namespace syntax SpeedCondition::SpeedCondition( const pugi::xml_node & node, Scope & scope, const TriggeringEntities & triggering_entities) : Scope(scope), + rule(readAttribute("rule", node, scope)), value(readAttribute("value", node, scope)), - compare(readAttribute("rule", node, scope)), + direction(readAttribute("direction", node, scope, std::nullopt)), triggering_entities(triggering_entities), - results(triggering_entities.entity_refs.size(), Double::nan()) + evaluations(triggering_entities.entity_refs.size(), Double::nan()) { } @@ -40,18 +42,32 @@ auto SpeedCondition::description() const -> String description << triggering_entities.description() << "'s speed = "; - print_to(description, results); + print_to(description, evaluations); - description << " " << compare << " " << value << "?"; + description << " " << rule << " " << value << "?"; return description.str(); } -auto SpeedCondition::evaluate(const EntityRef & triggering_entity, const Entities * entities) - -> double +auto SpeedCondition::evaluate( + const EntityRef & triggering_entity, const Entities * entities, + const std::optional & direction) -> double { - if (entities->ref(triggering_entity).as().is_added) { - return evaluateSpeed(triggering_entity); + if (entities->isAdded(triggering_entity)) { + if (const auto v = evaluateSpeed(triggering_entity); direction) { + switch (*direction) { + case DirectionalDimension::longitudinal: + return v.x; + case DirectionalDimension::lateral: + return v.y; + case DirectionalDimension::vertical: + return v.z; + default: + return math::geometry::norm(v); + } + } else { + return math::geometry::norm(v); + } } else { return Double::nan(); } @@ -59,11 +75,11 @@ auto SpeedCondition::evaluate(const EntityRef & triggering_entity, const Entitie auto SpeedCondition::evaluate() -> Object { - results.clear(); + evaluations.clear(); return asBoolean(triggering_entities.apply([&](auto && triggering_entity) { - results.push_back(evaluate(triggering_entity, global().entities)); - return compare(results.back(), value); + evaluations.push_back(evaluate(triggering_entity, global().entities)); + return std::invoke(rule, evaluations.back(), value); })); } } // namespace syntax diff --git a/openscenario/openscenario_interpreter/src/syntax/speed_profile_action.cpp b/openscenario/openscenario_interpreter/src/syntax/speed_profile_action.cpp index accb647abf7..214e274fcbb 100644 --- a/openscenario/openscenario_interpreter/src/syntax/speed_profile_action.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/speed_profile_action.cpp @@ -15,6 +15,7 @@ #include #include #include +#include #include namespace openscenario_interpreter @@ -100,10 +101,12 @@ auto SpeedProfileAction::run() -> void for (auto && [actor, iter] : accomplishments) { auto accomplished = [this](const auto & actor, const auto & speed_profile_entry) { if (entity_ref.empty()) { - return equal_to()(evaluateSpeed(actor), speed_profile_entry.speed); + return equal_to()( + SpeedCondition::evaluate(actor, global().entities), speed_profile_entry.speed); } else { return equal_to()( - evaluateSpeed(actor), speed_profile_entry.speed + evaluateSpeed(entity_ref)); + SpeedCondition::evaluate(actor, global().entities), + speed_profile_entry.speed + SpeedCondition::evaluate(entity_ref, global().entities)); } }; From cddc3a52c475717a36249c6b837f29ccbbe2bf73 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 5 Jul 2024 17:11:22 +0900 Subject: [PATCH 13/25] Move function `hypot` into new header `cmath/hypot.hpp` Signed-off-by: yamacir-kit --- .../openscenario_interpreter/cmath/hypot.hpp | 44 +++++++++++++++++++ .../syntax/reach_position_condition.hpp | 2 - .../syntax/relative_speed_condition.hpp | 2 +- .../syntax/time_to_collision_condition.hpp | 2 +- .../src/syntax/distance_condition.cpp | 15 +------ .../src/syntax/reach_position_condition.cpp | 22 +++------- .../syntax/relative_distance_condition.cpp | 13 +----- 7 files changed, 55 insertions(+), 45 deletions(-) create mode 100644 openscenario/openscenario_interpreter/include/openscenario_interpreter/cmath/hypot.hpp diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/cmath/hypot.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/cmath/hypot.hpp new file mode 100644 index 00000000000..23a19b9e0c9 --- /dev/null +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/cmath/hypot.hpp @@ -0,0 +1,44 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef OPENSCENARIO_INTERPRETER__CMATH__HYPOT_HPP_ +#define OPENSCENARIO_INTERPRETER__CMATH__HYPOT_HPP_ + +#include +#include + +namespace openscenario_interpreter +{ +inline namespace cmath +{ +/* + @todo: after checking all the scenario work well with + consider_pose_by_road_slope = true, remove this function and use + std::hypot(x, y, z) +*/ +template +auto hypot(T x, T y, T z) +{ + static const auto consider_pose_by_road_slope = []() { + auto node = rclcpp::Node("get_parameter", "simulation"); + node.declare_parameter("consider_pose_by_road_slope", false); + return node.get_parameter("consider_pose_by_road_slope").as_bool(); + }(); + + return consider_pose_by_road_slope ? std::hypot(x, y, z) : std::hypot(x, y); +} +} // namespace cmath +} // namespace openscenario_interpreter + +#endif // OPENSCENARIO_INTERPRETER__CMATH__HYPOT_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/reach_position_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/reach_position_condition.hpp index 527614ad500..35e98272ce5 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/reach_position_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/reach_position_condition.hpp @@ -49,8 +49,6 @@ struct ReachPositionCondition : private SimulatorCore::CoordinateSystemConversio std::vector results; // for description - const bool consider_z; - explicit ReachPositionCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &); auto description() const -> String; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp index d42b50db0dd..a485b3e315b 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp @@ -74,7 +74,7 @@ struct RelativeSpeedCondition : private Scope, private SimulatorCore::ConditionE static auto evaluate( const EntityRef &, const EntityRef &, const Entities *, - const std::optional &) -> double; + const std::optional & = std::nullopt) -> double; auto evaluate() -> Object; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp index 23140651a67..c6f70c43ac3 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -135,7 +135,7 @@ struct TimeToCollisionCondition : private Scope, private SimulatorCore::Conditio << ", RELATIVE SPEED = " << RelativeSpeedCondition::evaluate( triggering_entity, time_to_collision_condition_target.as(), - global().entities, std::nullopt) + global().entities) << std::endl; } else { std::cerr << "DISTANCE = " diff --git a/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp index 4621497b6f0..3c6479e12ff 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include #include #include @@ -130,23 +130,12 @@ auto DistanceCondition::evaluate( if (entities->ref(triggering_entity).as().is_added) { SWITCH_COORDINATE_SYSTEM( SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); + return Double::nan(); } else { return Double::nan(); } } -// @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x,y,z) -static auto hypot(const double x, const double y, const double z) -{ - static auto consider_z = []() { - auto node = rclcpp::Node("get_parameter", "simulation"); - node.declare_parameter("consider_pose_by_road_slope", false); - return node.get_parameter("consider_pose_by_road_slope").as_bool(); - }(); - - return consider_z ? std::hypot(x, y, z) : std::hypot(x, y); -} - template <> auto DistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, diff --git a/openscenario/openscenario_interpreter/src/syntax/reach_position_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/reach_position_condition.cpp index 07dc4e81d06..08d7000c86e 100644 --- a/openscenario/openscenario_interpreter/src/syntax/reach_position_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/reach_position_condition.cpp @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include #include @@ -31,12 +32,7 @@ ReachPositionCondition::ReachPositionCondition( position(readElement("Position", node, scope)), compare(Rule::lessThan), triggering_entities(triggering_entities), - results(triggering_entities.entity_refs.size(), Double::nan()), - consider_z([]() { - rclcpp::Node node{"get_parameter", "simulation"}; - node.declare_parameter("consider_pose_by_road_slope", false); - return node.get_parameter("consider_pose_by_road_slope").as_bool(); - }()) + results(triggering_entities.entity_refs.size(), Double::nan()) { } @@ -53,12 +49,6 @@ auto ReachPositionCondition::description() const -> String return description.str(); } -// @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x,y,z) -static double hypot(const double x, const double y, const double z, const bool consider_z) -{ - return consider_z ? std::hypot(x, y, z) : std::hypot(x, y); -} - auto ReachPositionCondition::evaluate() -> Object { // TODO USE DistanceCondition::distance @@ -66,22 +56,22 @@ auto ReachPositionCondition::evaluate() -> Object [&](const WorldPosition & position, auto && triggering_entity) { const auto pose = makeNativeRelativeWorldPosition( triggering_entity, static_cast(position)); - return hypot(pose.position.x, pose.position.y, pose.position.z, consider_z); + return hypot(pose.position.x, pose.position.y, pose.position.z); }, [&](const RelativeWorldPosition & position, auto && triggering_entity) { const auto pose = makeNativeRelativeWorldPosition( triggering_entity, static_cast(position)); - return hypot(pose.position.x, pose.position.y, pose.position.z, consider_z); + return hypot(pose.position.x, pose.position.y, pose.position.z); }, [&](const RelativeObjectPosition & position, auto && triggering_entity) { const auto pose = makeNativeRelativeWorldPosition( triggering_entity, static_cast(position)); - return hypot(pose.position.x, pose.position.y, pose.position.z, consider_z); + return hypot(pose.position.x, pose.position.y, pose.position.z); }, [&](const LanePosition & position, auto && triggering_entity) { const auto pose = makeNativeRelativeWorldPosition( triggering_entity, static_cast(position)); - return hypot(pose.position.x, pose.position.y, pose.position.z, consider_z); + return hypot(pose.position.x, pose.position.y, pose.position.z); }); results.clear(); diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index 36203a6479b..b9b3b535a0a 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include #include // TEMPORARY (TODO REMOVE THIS LINE) @@ -105,18 +106,6 @@ auto RelativeDistanceCondition::distance< makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y); } -// @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x, y, z) -auto hypot(double x, double y, double z) -{ - static auto consider_z = []() { - auto node = rclcpp::Node("get_parameter", "simulation"); - node.declare_parameter("consider_pose_by_road_slope", false); - return node.get_parameter("consider_pose_by_road_slope").as_bool(); - }(); - - return consider_z ? std::hypot(x, y, z) : std::hypot(x, y); -} - template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, From 5018106f2b92152ff2d49b0e038c252665af488c Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 5 Jul 2024 18:11:04 +0900 Subject: [PATCH 14/25] Update `unordered_map` of the `Entities` base class to private Signed-off-by: yamacir-kit --- .../syntax/entities.hpp | 28 +++++++++++-------- .../src/syntax/add_entity_action.cpp | 2 +- .../syntax/relative_distance_condition.cpp | 4 +-- .../src/syntax/relative_speed_condition.cpp | 4 +-- .../src/syntax/teleport_action.cpp | 2 +- 5 files changed, 21 insertions(+), 19 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/entities.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/entities.hpp index a8abbd1dc91..27a65121a24 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/entities.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/entities.hpp @@ -23,18 +23,24 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- Entities --------------------------------------------------------------- - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ -struct Entities : public std::unordered_map // TODO to be data member +/* + Entities (OpenSCENARIO XML 1.3) + + Definition of entities (scenario objects or entity selections) in + a scenario. + + + + + + + +*/ +struct Entities : private std::unordered_map { + using std::unordered_map::begin; + using std::unordered_map::end; + explicit Entities(const pugi::xml_node &, Scope &); auto isAdded(const EntityRef &) const -> bool; diff --git a/openscenario/openscenario_interpreter/src/syntax/add_entity_action.cpp b/openscenario/openscenario_interpreter/src/syntax/add_entity_action.cpp index d0408597bf5..ae11d05f50c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/add_entity_action.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/add_entity_action.cpp @@ -47,7 +47,7 @@ auto AddEntityAction::endsImmediately() noexcept -> bool // auto AddEntityAction::operator()(const EntityRef & entity_ref) const -> void try { - const auto entity = global().entities->at(entity_ref); + const auto entity = global().entities->ref(entity_ref); const auto add_entity = overload( [&](const Vehicle & vehicle) { diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index b9b3b535a0a..558affe0730 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -321,9 +321,7 @@ auto RelativeDistanceCondition::evaluate( CoordinateSystem coordinate_system, RelativeDistanceType relative_distance_type, RoutingAlgorithm routing_algorithm, bool freespace) -> double { - if ( - entities->at(triggering_entity).as().is_added and - entities->at(entity_ref).as().is_added) { + if (entities->isAdded(triggering_entity) and entities->isAdded(entity_ref)) { SWITCH_COORDINATE_SYSTEM( SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); } else { diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp index 0e7d30bd03f..748b5ba179c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp @@ -57,9 +57,7 @@ auto RelativeSpeedCondition::evaluate( const EntityRef & triggering_entity, const EntityRef & entity_ref, const Entities * entities, const std::optional & direction) -> double { - if ( - entities->at(triggering_entity).as().is_added and - entities->at(entity_ref).as().is_added) { + if (entities->isAdded(triggering_entity) and entities->isAdded(entity_ref)) { if (const auto v = evaluateRelativeSpeed(triggering_entity, entity_ref); direction) { switch (*direction) { case DirectionalDimension::longitudinal: diff --git a/openscenario/openscenario_interpreter/src/syntax/teleport_action.cpp b/openscenario/openscenario_interpreter/src/syntax/teleport_action.cpp index 4e59e603519..8d150d0c919 100644 --- a/openscenario/openscenario_interpreter/src/syntax/teleport_action.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/teleport_action.cpp @@ -44,7 +44,7 @@ auto TeleportAction::run() noexcept -> void {} auto TeleportAction::start() const -> void { for (const auto & actor : actors) { - if (not global().entities->at(actor).as().is_added) { + if (not global().entities->isAdded(actor)) { AddEntityAction(local(), position)(actor); // NOTE: TIER IV extension } else { return teleport(actor, position); From fdae8b4dee1109e33c22ec71ac14ef189e84ffae Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Mon, 8 Jul 2024 12:41:28 +0900 Subject: [PATCH 15/25] Add new static member function `TimeToCollisionCondition::evaluate` Signed-off-by: yamacir-kit --- .../syntax/distance_condition.hpp | 4 +- .../syntax/relative_distance_condition.hpp | 4 +- .../syntax/relative_speed_condition.hpp | 2 +- .../syntax/speed_condition.hpp | 2 +- .../syntax/time_to_collision_condition.hpp | 75 ++++++++++++------- .../src/syntax/distance_condition.cpp | 6 +- .../syntax/relative_distance_condition.cpp | 6 +- .../src/syntax/relative_speed_condition.cpp | 4 +- .../src/syntax/speed_action.cpp | 10 +-- .../src/syntax/speed_condition.cpp | 4 +- .../src/syntax/speed_profile_action.cpp | 6 +- 11 files changed, 70 insertions(+), 53 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp index 453a31fed35..1c72887b355 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distance_condition.hpp @@ -120,8 +120,8 @@ struct DistanceCondition : private Scope, private SimulatorCore::ConditionEvalua } static auto evaluate( - const EntityRef &, const Position &, const Entities *, CoordinateSystem, RelativeDistanceType, - RoutingAlgorithm, bool) -> double; + const Entities *, const EntityRef &, const Position &, CoordinateSystem, RelativeDistanceType, + RoutingAlgorithm, Boolean) -> double; auto evaluate() -> Object; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp index bf09beca6d2..8dea6e12dad 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp @@ -103,8 +103,8 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi } static auto evaluate( - const EntityRef &, const EntityRef &, const Entities *, CoordinateSystem, RelativeDistanceType, - RoutingAlgorithm, bool) -> double; + const Entities *, const EntityRef &, const EntityRef &, CoordinateSystem, RelativeDistanceType, + RoutingAlgorithm, Boolean) -> double; auto evaluate() -> Object; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp index a485b3e315b..1fb90aaef54 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp @@ -73,7 +73,7 @@ struct RelativeSpeedCondition : private Scope, private SimulatorCore::ConditionE auto description() const -> String; static auto evaluate( - const EntityRef &, const EntityRef &, const Entities *, + const Entities *, const EntityRef &, const EntityRef &, const std::optional & = std::nullopt) -> double; auto evaluate() -> Object; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp index 7a776f2c0c2..874951d4c5a 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp @@ -68,7 +68,7 @@ struct SpeedCondition : private Scope, private SimulatorCore::ConditionEvaluatio auto description() const -> String; static auto evaluate( - const EntityRef &, const Entities *, const std::optional & = std::nullopt) + const Entities *, const EntityRef &, const std::optional & = std::nullopt) -> double; auto evaluate() -> Object; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp index c6f70c43ac3..e460d8d6fb7 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -117,40 +117,57 @@ struct TimeToCollisionCondition : private Scope, private SimulatorCore::Conditio return description.str(); } + static auto evaluate( + const Entities * entities, const EntityRef & triggering_entity, + const TimeToCollisionConditionTarget & time_to_collision_condition_target, + CoordinateSystem coordinate_system, RelativeDistanceType relative_distance_type, + RoutingAlgorithm routing_algorithm, Boolean freespace) + { + if (time_to_collision_condition_target.is()) { + const auto relative_distance = RelativeDistanceCondition::evaluate( + entities, // + triggering_entity, // + time_to_collision_condition_target.as(), // + coordinate_system, // + relative_distance_type, // + routing_algorithm, // + freespace); + + const auto relative_speed = RelativeSpeedCondition::evaluate( + entities, // + triggering_entity, // + time_to_collision_condition_target.as()); + + std::cerr << "RELATIVE DISTANCE = " << relative_distance + << ", RELATIVE SPEED = " << relative_speed << std::endl; + + return relative_distance / relative_speed; + } else { + const auto distance = DistanceCondition::evaluate( + entities, // + triggering_entity, // + time_to_collision_condition_target.as(), // + coordinate_system, // + relative_distance_type, // + routing_algorithm, // + freespace); + + const auto speed = SpeedCondition::evaluate(entities, triggering_entity); + + std::cerr << "DISTANCE = " << distance << ", RELATIVE SPEED = " << speed << std::endl; + + return distance / speed; + } + } + auto evaluate() { evaluations.clear(); return asBoolean(triggering_entities.apply([this](auto && triggering_entity) { - [[deprecated]] auto evaluateTimeToCollision = - [this]( - const EntityRef & triggering_entity, - const TimeToCollisionConditionTarget & time_to_collision_condition_target) { - if (time_to_collision_condition_target.is()) { - std::cerr << "RELATIVE DISTANCE = " - << RelativeDistanceCondition::evaluate( - triggering_entity, time_to_collision_condition_target.as(), - global().entities, coordinate_system, relative_distance_type, - routing_algorithm, freespace) - << ", RELATIVE SPEED = " - << RelativeSpeedCondition::evaluate( - triggering_entity, time_to_collision_condition_target.as(), - global().entities) - << std::endl; - } else { - std::cerr << "DISTANCE = " - << DistanceCondition::evaluate( - triggering_entity, time_to_collision_condition_target.as(), - global().entities, coordinate_system, relative_distance_type, - routing_algorithm, freespace) - << ", RELATIVE SPEED = " - << SpeedCondition::evaluate(triggering_entity, global().entities) - << std::endl; - } - return Double(); - }; - evaluations.push_back( - evaluateTimeToCollision(triggering_entity, time_to_collision_condition_target)); + evaluations.push_back(evaluate( + global().entities, triggering_entity, time_to_collision_condition_target, coordinate_system, + relative_distance_type, routing_algorithm, freespace)); return std::invoke(rule, evaluations.back(), value); })); } diff --git a/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp index 3c6479e12ff..6df2d9c64f6 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distance_condition.cpp @@ -123,9 +123,9 @@ auto DistanceCondition::description() const -> std::string #define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity, position) auto DistanceCondition::evaluate( - const EntityRef & triggering_entity, const Position & position, const Entities * entities, + const Entities * entities, const EntityRef & triggering_entity, const Position & position, CoordinateSystem coordinate_system, RelativeDistanceType relative_distance_type, - RoutingAlgorithm routing_algorithm, bool freespace) -> double + RoutingAlgorithm routing_algorithm, Boolean freespace) -> double { if (entities->ref(triggering_entity).as().is_added) { SWITCH_COORDINATE_SYSTEM( @@ -610,7 +610,7 @@ auto DistanceCondition::evaluate() -> Object return asBoolean(triggering_entities.apply([&](auto && triggering_entity) { results.push_back(evaluate( - triggering_entity, position, global().entities, coordinate_system, relative_distance_type, + global().entities, triggering_entity, position, coordinate_system, relative_distance_type, routing_algorithm, freespace)); return rule(static_cast(results.back()), value); })); diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index 558affe0730..dea1883ad25 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -317,9 +317,9 @@ auto RelativeDistanceCondition::distance< #define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity, entity_ref) auto RelativeDistanceCondition::evaluate( - const EntityRef & triggering_entity, const EntityRef & entity_ref, const Entities * entities, + const Entities * entities, const EntityRef & triggering_entity, const EntityRef & entity_ref, CoordinateSystem coordinate_system, RelativeDistanceType relative_distance_type, - RoutingAlgorithm routing_algorithm, bool freespace) -> double + RoutingAlgorithm routing_algorithm, Boolean freespace) -> double { if (entities->isAdded(triggering_entity) and entities->isAdded(entity_ref)) { SWITCH_COORDINATE_SYSTEM( @@ -335,7 +335,7 @@ auto RelativeDistanceCondition::evaluate() -> Object return asBoolean(triggering_entities.apply([&](const auto & triggering_entity) { results.push_back(evaluate( - triggering_entity, entity_ref, global().entities, coordinate_system, relative_distance_type, + global().entities, triggering_entity, entity_ref, coordinate_system, relative_distance_type, routing_algorithm, freespace)); return rule(static_cast(results.back()), value); })); diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp index 748b5ba179c..32b3781dbe5 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp @@ -54,7 +54,7 @@ auto RelativeSpeedCondition::description() const -> String } auto RelativeSpeedCondition::evaluate( - const EntityRef & triggering_entity, const EntityRef & entity_ref, const Entities * entities, + const Entities * entities, const EntityRef & triggering_entity, const EntityRef & entity_ref, const std::optional & direction) -> double { if (entities->isAdded(triggering_entity) and entities->isAdded(entity_ref)) { @@ -82,7 +82,7 @@ auto RelativeSpeedCondition::evaluate() -> Object evaluations.clear(); return asBoolean(triggering_entities.apply([this](auto && triggering_entity) { - evaluations.push_back(evaluate(triggering_entity, entity_ref, global().entities, direction)); + evaluations.push_back(evaluate(global().entities, triggering_entity, entity_ref, direction)); return std::invoke(rule, evaluations.back(), value); })); } diff --git a/openscenario/openscenario_interpreter/src/syntax/speed_action.cpp b/openscenario/openscenario_interpreter/src/syntax/speed_action.cpp index c3a10522d76..90133eaa5d9 100644 --- a/openscenario/openscenario_interpreter/src/syntax/speed_action.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/speed_action.cpp @@ -47,21 +47,21 @@ auto SpeedAction::accomplished() -> bool if (speed_action_target.is()) { return equal_to()( speed_action_target.as().value, - SpeedCondition::evaluate(actor, global().entities)); + SpeedCondition::evaluate(global().entities, actor)); } else { switch (speed_action_target.as().speed_target_value_type) { case SpeedTargetValueType::delta: return equal_to()( SpeedCondition::evaluate( - speed_action_target.as().entity_ref, global().entities) + + global().entities, speed_action_target.as().entity_ref) + speed_action_target.as().value, - SpeedCondition::evaluate(actor, global().entities)); + SpeedCondition::evaluate(global().entities, actor)); case SpeedTargetValueType::factor: return equal_to()( SpeedCondition::evaluate( - speed_action_target.as().entity_ref, global().entities) * + global().entities, speed_action_target.as().entity_ref) * speed_action_target.as().value, - SpeedCondition::evaluate(actor, global().entities)); + SpeedCondition::evaluate(global().entities, actor)); default: return false; } diff --git a/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp index 1e8ebcdf228..505504398f9 100644 --- a/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp @@ -50,7 +50,7 @@ auto SpeedCondition::description() const -> String } auto SpeedCondition::evaluate( - const EntityRef & triggering_entity, const Entities * entities, + const Entities * entities, const EntityRef & triggering_entity, const std::optional & direction) -> double { if (entities->isAdded(triggering_entity)) { @@ -78,7 +78,7 @@ auto SpeedCondition::evaluate() -> Object evaluations.clear(); return asBoolean(triggering_entities.apply([&](auto && triggering_entity) { - evaluations.push_back(evaluate(triggering_entity, global().entities)); + evaluations.push_back(evaluate(global().entities, triggering_entity)); return std::invoke(rule, evaluations.back(), value); })); } diff --git a/openscenario/openscenario_interpreter/src/syntax/speed_profile_action.cpp b/openscenario/openscenario_interpreter/src/syntax/speed_profile_action.cpp index 214e274fcbb..0e0ed7dd509 100644 --- a/openscenario/openscenario_interpreter/src/syntax/speed_profile_action.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/speed_profile_action.cpp @@ -102,11 +102,11 @@ auto SpeedProfileAction::run() -> void auto accomplished = [this](const auto & actor, const auto & speed_profile_entry) { if (entity_ref.empty()) { return equal_to()( - SpeedCondition::evaluate(actor, global().entities), speed_profile_entry.speed); + SpeedCondition::evaluate(global().entities, actor), speed_profile_entry.speed); } else { return equal_to()( - SpeedCondition::evaluate(actor, global().entities), - speed_profile_entry.speed + SpeedCondition::evaluate(entity_ref, global().entities)); + SpeedCondition::evaluate(global().entities, actor), + speed_profile_entry.speed + SpeedCondition::evaluate(global().entities, entity_ref)); } }; From 2656a5a38a964181b9605374fefceb3431f2b131 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 22 Nov 2024 10:35:28 +0900 Subject: [PATCH 16/25] Split `(Relative)?DistanceCondition::evaluate` into two overloads Signed-off-by: yamacir-kit --- .../syntax/relative_speed_condition.hpp | 7 +- .../syntax/speed_condition.hpp | 5 +- .../syntax/time_to_collision_condition.hpp | 68 +++++++++---------- .../src/syntax/relative_speed_condition.cpp | 41 ++++++----- .../src/syntax/speed_action.cpp | 11 +-- .../src/syntax/speed_condition.cpp | 40 ++++++----- .../src/syntax/speed_profile_action.cpp | 7 +- 7 files changed, 102 insertions(+), 77 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp index 5920e0ed3b7..a7e118bbb3b 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_speed_condition.hpp @@ -72,9 +72,12 @@ struct RelativeSpeedCondition : private Scope, private SimulatorCore::ConditionE auto description() const -> String; + static auto evaluate(const Entities *, const Entity &, const Entity &) + -> geometry_msgs::msg::Vector3; + static auto evaluate( - const Entities *, const Entity &, const Entity &, - const std::optional & = std::nullopt) -> double; + const Entities *, const Entity &, const Entity &, const std::optional &) + -> double; auto evaluate() -> Object; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp index 05a87962d34..d674955a105 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp @@ -68,9 +68,10 @@ struct SpeedCondition : private Scope, private SimulatorCore::ConditionEvaluatio auto description() const -> String; + static auto evaluate(const Entities *, const Entity &) -> geometry_msgs::msg::Vector3; + static auto evaluate( - const Entities *, const Entity &, const std::optional & = std::nullopt) - -> double; + const Entities *, const Entity &, const std::optional &) -> double; auto evaluate() -> Object; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp index 61a1b0a76b5..e6e67c8a815 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -123,40 +123,40 @@ struct TimeToCollisionCondition : private Scope, private SimulatorCore::Conditio CoordinateSystem coordinate_system, RelativeDistanceType relative_distance_type, RoutingAlgorithm routing_algorithm, Boolean freespace) { - if (time_to_collision_condition_target.is()) { - const auto relative_distance = RelativeDistanceCondition::evaluate( - entities, // - triggering_entity, // - time_to_collision_condition_target.as(), // - coordinate_system, // - relative_distance_type, // - routing_algorithm, // - freespace); - - const auto relative_speed = RelativeSpeedCondition::evaluate( - entities, // - triggering_entity, // - time_to_collision_condition_target.as()); - - // std::cerr << "RELATIVE DISTANCE = " << relative_distance - // << ", RELATIVE SPEED = " << relative_speed << std::endl; - - return relative_distance / relative_speed; - } else { - const auto distance = DistanceCondition::evaluate( - entities, // - triggering_entity, // - time_to_collision_condition_target.as(), // - coordinate_system, // - relative_distance_type, // - routing_algorithm, // - freespace); - - const auto speed = SpeedCondition::evaluate(entities, triggering_entity); - - // std::cerr << "DISTANCE = " << distance << ", RELATIVE SPEED = " << speed << std::endl; - - return distance / speed; + auto distance = [&]() { + if (time_to_collision_condition_target.is()) { + return RelativeDistanceCondition::evaluate( + entities, triggering_entity, time_to_collision_condition_target.as(), + coordinate_system, relative_distance_type, routing_algorithm, freespace); + } else { + return DistanceCondition::evaluate( + entities, triggering_entity, time_to_collision_condition_target.as(), + coordinate_system, relative_distance_type, routing_algorithm, freespace); + } + }; + + auto speed = [&](auto &&... xs) { + if (time_to_collision_condition_target.is()) { + return RelativeSpeedCondition::evaluate( + entities, // + triggering_entity, // + time_to_collision_condition_target.as(), std::forward(xs)...); + } else { + return SpeedCondition::evaluate( + entities, triggering_entity, std::forward(xs)...); + } + }; + + switch (relative_distance_type) { + case RelativeDistanceType::longitudinal: + return distance() / speed(DirectionalDimension::longitudinal); + + case RelativeDistanceType::lateral: + return distance() / speed(DirectionalDimension::lateral); + + default: + case RelativeDistanceType::euclidianDistance: + return distance() / speed(std::nullopt); } } diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp index a9c6d49be05..e61c643ccf2 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp @@ -58,28 +58,37 @@ auto RelativeSpeedCondition::description() const -> String } auto RelativeSpeedCondition::evaluate( - const Entities * entities, const Entity & triggering_entity, const Entity & entity_ref, - const std::optional & direction) -> double + const Entities * entities, const Entity & triggering_entity, const Entity & entity_ref) + -> geometry_msgs::msg::Vector3 { if ( triggering_entity.apply([&](const auto & each) { return entities->isAdded(each); }).min() and entities->isAdded(entity_ref)) { - if (const auto v = evaluateRelativeSpeed(triggering_entity, entity_ref); direction) { - switch (*direction) { - case DirectionalDimension::longitudinal: - return v.x; - case DirectionalDimension::lateral: - return v.y; - case DirectionalDimension::vertical: - return v.z; - default: - return math::geometry::norm(v); - } - } else { - return math::geometry::norm(v); + return evaluateRelativeSpeed(triggering_entity, entity_ref); + } else { + return geometry_msgs::build() + .x(Double::nan()) + .y(Double::nan()) + .z(Double::nan()); + } +} + +auto RelativeSpeedCondition::evaluate( + const Entities * entities, const Entity & triggering_entity, const Entity & entity_ref, + const std::optional & direction) -> double +{ + if (const auto v = evaluate(entities, triggering_entity, entity_ref); direction) { + switch (*direction) { + default: + case DirectionalDimension::longitudinal: + return v.x; + case DirectionalDimension::lateral: + return v.y; + case DirectionalDimension::vertical: + return v.z; } } else { - return Double::nan(); + return math::geometry::norm(v); } } diff --git a/openscenario/openscenario_interpreter/src/syntax/speed_action.cpp b/openscenario/openscenario_interpreter/src/syntax/speed_action.cpp index a0811838241..777fde3e70a 100644 --- a/openscenario/openscenario_interpreter/src/syntax/speed_action.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/speed_action.cpp @@ -56,8 +56,9 @@ auto SpeedAction::accomplished() -> bool }; auto check = [this](auto && actor) { - auto evaluation = actor.apply( - [this](const auto & actor) { return SpeedCondition::evaluate(global().entities, actor); }); + auto evaluation = actor.apply([this](const auto & actor) { + return SpeedCondition::evaluate(global().entities, actor, std::nullopt); + }); if (speed_action_target.is()) { return not evaluation.size() or equal_to>()( @@ -69,7 +70,8 @@ auto SpeedAction::accomplished() -> bool return not evaluation.size() or equal_to>()( SpeedCondition::evaluate( - global().entities, speed_action_target.as().entity_ref) + + global().entities, speed_action_target.as().entity_ref, + std::nullopt) + speed_action_target.as().value, evaluation) .min(); @@ -77,7 +79,8 @@ auto SpeedAction::accomplished() -> bool return not evaluation.size() or equal_to>()( SpeedCondition::evaluate( - global().entities, speed_action_target.as().entity_ref) * + global().entities, speed_action_target.as().entity_ref, + std::nullopt) * speed_action_target.as().value, evaluation) .min(); diff --git a/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp index dd4c858269b..a392505abb5 100644 --- a/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp @@ -49,27 +49,35 @@ auto SpeedCondition::description() const -> String return description.str(); } +auto SpeedCondition::evaluate(const Entities * entities, const Entity & triggering_entity) + -> geometry_msgs::msg::Vector3 +{ + if (entities->isAdded(triggering_entity)) { + return evaluateSpeed(triggering_entity); + } else { + return geometry_msgs::build() + .x(Double::nan()) + .y(Double::nan()) + .z(Double::nan()); + } +} + auto SpeedCondition::evaluate( const Entities * entities, const Entity & triggering_entity, const std::optional & direction) -> double { - if (entities->isAdded(triggering_entity)) { - if (const auto v = evaluateSpeed(triggering_entity); direction) { - switch (*direction) { - case DirectionalDimension::longitudinal: - return v.x; - case DirectionalDimension::lateral: - return v.y; - case DirectionalDimension::vertical: - return v.z; - default: - return math::geometry::norm(v); - } - } else { - return math::geometry::norm(v); + if (const auto v = evaluate(entities, triggering_entity); direction) { + switch (*direction) { + default: + case DirectionalDimension::longitudinal: + return v.x; + case DirectionalDimension::lateral: + return v.y; + case DirectionalDimension::vertical: + return v.z; } } else { - return Double::nan(); + return math::geometry::norm(v); } } @@ -79,7 +87,7 @@ auto SpeedCondition::evaluate() -> Object return asBoolean(triggering_entities.apply([&](auto && triggering_entity) { results.push_back(triggering_entity.apply([&](const auto & triggering_entity) { - return evaluate(global().entities, triggering_entity); + return evaluate(global().entities, triggering_entity, direction); })); return not results.back().size() or std::invoke(rule, results.back(), value).min(); })); diff --git a/openscenario/openscenario_interpreter/src/syntax/speed_profile_action.cpp b/openscenario/openscenario_interpreter/src/syntax/speed_profile_action.cpp index 4e241addd8b..eff38064c90 100644 --- a/openscenario/openscenario_interpreter/src/syntax/speed_profile_action.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/speed_profile_action.cpp @@ -121,14 +121,15 @@ auto SpeedProfileAction::run() -> void { for (auto && [actor, iter] : accomplishments) { auto accomplished = [this](const auto & actor, const auto & speed_profile_entry) { - auto speeds = actor.apply( - [&](const auto & object) { return SpeedCondition::evaluate(global().entities, object); }); + auto speeds = actor.apply([&](const auto & object) { + return SpeedCondition::evaluate(global().entities, object, std::nullopt); + }); if (not speeds.size()) { return true; } else if (entity_ref) { return equal_to>()( speeds, speed_profile_entry.speed + - SpeedCondition::evaluate(global().entities, entity_ref)) + SpeedCondition::evaluate(global().entities, entity_ref, std::nullopt)) .min(); } else { return equal_to>()(speeds, speed_profile_entry.speed).min(); From b8a9e63dd96d3ccb8cf32812f57b779ee1fdf4d5 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Mon, 25 Nov 2024 18:18:15 +0900 Subject: [PATCH 17/25] Add new member function `evaluateCartesianTimeToCollisionCondition` Signed-off-by: yamacir-kit --- .../simulator_core.hpp | 125 +++++++++++++++++- .../syntax/time_to_collision_condition.hpp | 29 +++- .../src/syntax/relative_speed_condition.cpp | 8 +- .../scenario_test_runner/config/workflow.txt | 1 + 4 files changed, 157 insertions(+), 6 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index 6fd055886fc..628c7a9c6a4 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -15,11 +15,14 @@ #ifndef OPENSCENARIO_INTERPRETER__SIMULATOR_CORE_HPP_ #define OPENSCENARIO_INTERPRETER__SIMULATOR_CORE_HPP_ +#include #include +#include #include #include #include #include +#include #include #include #include @@ -528,6 +531,90 @@ class SimulatorCore return core->getCurrentAccel(std::forward(xs)...).linear.x; } + static auto evaluateCartesianTimeToCollisionCondition(const Entity & from, const Entity & to) + { + if (const auto entity_a = core->getEntity(from.name())) { + if (const auto entity_b = core->getEntity(to.name())) { + struct OrientedBoundingBox + { + Eigen::Vector3d position; + + Eigen::Matrix3d rotation; + + Eigen::Vector3d size; // [width, height, depth] + + explicit OrientedBoundingBox( + const geometry_msgs::msg::Pose & pose, + const traffic_simulator_msgs::msg::BoundingBox & box) + : position( + pose.position.x + box.center.x, pose.position.y + box.center.y, + pose.position.z + box.center.z), + rotation(math::geometry::getRotationMatrix(pose.orientation)), + size(box.dimensions.y / 2, box.dimensions.z / 2, box.dimensions.x / 2) + { + } + + auto axis(std::size_t index) const -> Eigen::Vector3d { return rotation.col(index); } + }; + + const Eigen::Vector3d v = [&]() { + const auto v = evaluateRelativeSpeed(from, to); + return Eigen::Vector3d(v.x, v.y, v.z); + }(); + + const auto a = OrientedBoundingBox(entity_a->getMapPose(), entity_a->getBoundingBox()); + const auto b = OrientedBoundingBox(entity_b->getMapPose(), entity_b->getBoundingBox()); + + const auto axes = std::array{ + a.axis(0), + b.axis(0), + + a.axis(1), + b.axis(1), + + a.axis(2), + b.axis(2), + + a.axis(0).cross(b.axis(0)), + a.axis(0).cross(b.axis(1)), + a.axis(0).cross(b.axis(2)), + + a.axis(1).cross(b.axis(0)), + a.axis(1).cross(b.axis(1)), + a.axis(1).cross(b.axis(2)), + + a.axis(2).cross(b.axis(0)), + a.axis(2).cross(b.axis(1)), + a.axis(2).cross(b.axis(2)), + }; + + auto t_min = std::numeric_limits::infinity(); + + Eigen::Vector3d d = b.position - a.position; + + for (const auto & axis : axes) { + auto project = [&](const auto & obb) { + return std::abs(axis.dot(obb.axis(0)) * obb.size(0)) + + std::abs(axis.dot(obb.axis(1)) * obb.size(1)) + + std::abs(axis.dot(obb.axis(2)) * obb.size(2)); + }; + + if (const auto relative_speed = v.dot(axis); relative_speed < 0) { + const auto separation = std::abs(d.dot(axis)) - project(a) - project(b); + + if (const auto t = separation / -relative_speed; 0 < t) { + t_min = std::min(t_min, t); + } + } + } + + return t_min; + } + } + + return std::numeric_limits::quiet_NaN(); + } + template static auto evaluateCollisionCondition(Ts &&... xs) -> bool { @@ -551,11 +638,41 @@ class SimulatorCore return std::numeric_limits::quiet_NaN(); } - template - static auto evaluateRelativeSpeed(const T & x, const U & y) + static auto evaluateRelativeSpeed(const Entity & from, const Entity & to) + -> geometry_msgs::msg::Vector3 { - using math::geometry::operator-; - return core->getCurrentTwist(x).linear - core->getCurrentTwist(y).linear; + auto direction = [](auto orientation) { + const auto euler_angle = math::geometry::convertQuaternionToEulerAngle(orientation); + + // clang-format off + const auto roll = euler_angle.x; + const auto pitch = euler_angle.y; + const auto yaw = euler_angle.z; + // clang-format on + + auto v = decltype(euler_angle)(); + + v.x = std::cos(yaw) * std::cos(pitch); + v.y = std::sin(yaw) * std::cos(pitch); + v.z = std::sin(pitch); + + return v; + }; + + if (const auto a = core->getEntity(from.name())) { + if (const auto b = core->getEntity(to.name())) { + using math::geometry::operator*; + using math::geometry::operator-; + + return direction(b->getMapPose().orientation) * b->getCurrentTwist().linear.x - + direction(a->getMapPose().orientation) * a->getCurrentTwist().linear.x; + } + } + + return geometry_msgs::build() + .x(Double::nan()) + .y(Double::nan()) + .z(Double::nan()); } template diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp index e6e67c8a815..087822fd67d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -149,14 +149,41 @@ struct TimeToCollisionCondition : private Scope, private SimulatorCore::Conditio switch (relative_distance_type) { case RelativeDistanceType::longitudinal: + /* + There is no need to treat the cases where the speed is zero, NaN, or + infinity specially. When zero, NaN, or infinity appear in the + denominator, the Time-To-Collision will be infinity, NaN, or zero, + respectively, which are the desired return values to distinguish + between "no collision after infinite time", "undefined", and + "already a collision". + */ return distance() / speed(DirectionalDimension::longitudinal); case RelativeDistanceType::lateral: + /* + There is no need to treat the cases where the speed is zero, NaN, or + infinity specially. When zero, NaN, or infinity appear in the + denominator, the Time-To-Collision will be infinity, NaN, or zero, + respectively, which are the desired return values to distinguish + between "no collision after infinite time", "undefined", and + "already a collision". + */ return distance() / speed(DirectionalDimension::lateral); default: case RelativeDistanceType::euclidianDistance: - return distance() / speed(std::nullopt); + if (time_to_collision_condition_target.is()) { + if (freespace) { + return evaluateCartesianTimeToCollisionCondition( + triggering_entity, time_to_collision_condition_target.as()); + } else { + // TODO + return std::numeric_limits::quiet_NaN(); + } + } else { + // TODO + return distance() / speed(std::nullopt); + } } } diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp index e61c643ccf2..a8fe32a054e 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_speed_condition.cpp @@ -64,7 +64,13 @@ auto RelativeSpeedCondition::evaluate( if ( triggering_entity.apply([&](const auto & each) { return entities->isAdded(each); }).min() and entities->isAdded(entity_ref)) { - return evaluateRelativeSpeed(triggering_entity, entity_ref); + /* + Relative speed is defined as speed_rel = speed(triggering entity) - + speed(reference entity) + + See: https://publications.pages.asam.net/standards/ASAM_OpenSCENARIO/ASAM_OpenSCENARIO_XML/latest/generated/content/RelativeSpeedCondition.html + */ + return evaluateRelativeSpeed(entity_ref, triggering_entity); } else { return geometry_msgs::build() .x(Double::nan()) diff --git a/test_runner/scenario_test_runner/config/workflow.txt b/test_runner/scenario_test_runner/config/workflow.txt index 5f7aba83593..58b17f8c17a 100644 --- a/test_runner/scenario_test_runner/config/workflow.txt +++ b/test_runner/scenario_test_runner/config/workflow.txt @@ -6,6 +6,7 @@ $(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityConditio $(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.RelativeDistanceCondition.yaml $(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml $(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition-back.yaml +$(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition-simple.yaml $(find-pkg-share scenario_test_runner)/scenario/ControllerAction.AssignControllerAction.yaml $(find-pkg-share scenario_test_runner)/scenario/LongitudinalAction.SpeedAction.yaml $(find-pkg-share scenario_test_runner)/scenario/Property.isBlind.yaml From 6bc50fea435ab716a9fdfc377ba48ab5c3d9629a Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 26 Nov 2024 10:31:23 +0900 Subject: [PATCH 18/25] Add new test scenario `...EntityCondition.TimeToCollisionCondition.yaml` Signed-off-by: yamacir-kit --- .../scenario_test_runner/config/workflow.txt | 2 +- ...ityCondition.TimeToCollisionCondition.yaml | 166 ++++++++++++++++++ 2 files changed, 167 insertions(+), 1 deletion(-) create mode 100644 test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml diff --git a/test_runner/scenario_test_runner/config/workflow.txt b/test_runner/scenario_test_runner/config/workflow.txt index 58b17f8c17a..da8d9cd0923 100644 --- a/test_runner/scenario_test_runner/config/workflow.txt +++ b/test_runner/scenario_test_runner/config/workflow.txt @@ -6,7 +6,7 @@ $(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityConditio $(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.RelativeDistanceCondition.yaml $(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml $(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition-back.yaml -$(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition-simple.yaml +$(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml $(find-pkg-share scenario_test_runner)/scenario/ControllerAction.AssignControllerAction.yaml $(find-pkg-share scenario_test_runner)/scenario/LongitudinalAction.SpeedAction.yaml $(find-pkg-share scenario_test_runner)/scenario/Property.isBlind.yaml diff --git a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml new file mode 100644 index 00000000000..da9326acb0f --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml @@ -0,0 +1,166 @@ +ScenarioModifiers: + ScenarioModifier: [] +OpenSCENARIO: + FileHeader: { revMajor: 1, revMinor: 1, date: '2024-11-25T04:18:18.703Z', description: '', author: Tatsuya Yamasaki } + ParameterDeclarations: + ParameterDeclaration: [] + CatalogLocations: + VehicleCatalog: + Directory: { path: $(ros2 pkg prefix --share openscenario_experimental_catalog)/vehicle } + RoadNetwork: + LogicFile: { filepath: $(ros2 pkg prefix --share kashiwanoha_map)/map } + Entities: + ScenarioObject: + - name: ego + CatalogReference: { catalogName: sample_vehicle, entryName: sample_vehicle } + ObjectController: + Controller: + name: '' + Properties: + Property: [] + - name: vehicle_01 + CatalogReference: { catalogName: sample_vehicle, entryName: sample_vehicle } + ObjectController: + Controller: + name: '' + Properties: + Property: [] + Storyboard: + Init: + Actions: + Private: + - entityRef: ego + PrivateAction: + - TeleportAction: + Position: + LanePosition: + roadId: '' + laneId: '34513' + s: 5 + offset: 0 + Orientation: + type: relative + h: 0 + p: 0 + r: 0 + - entityRef: vehicle_01 + PrivateAction: + - TeleportAction: + Position: + LanePosition: + roadId: '' + laneId: '34510' + s: 10 + offset: 0 + Orientation: + type: relative + h: 0 + p: 0 + r: 0 + - ControllerAction: + AssignControllerAction: + Controller: + name: '' + Properties: + Property: + - name: maxSpeed + value: '1' + Story: + - name: '' + Act: + - name: _EndCondition + ManeuverGroup: + - maximumExecutionCount: 1 + name: '' + Actors: + selectTriggeringEntities: false + EntityRef: + - entityRef: ego + Maneuver: + - name: '' + Event: + - name: '' + priority: parallel + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 20 + rule: greaterThan + Action: + - name: '' + UserDefinedAction: + CustomCommandAction: + type: exitSuccess + - name: '' + Event: + - name: '' + priority: parallel + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 180 + rule: greaterThan + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: [ entityRef: ego ] + EntityCondition: + TimeToCollisionCondition: + freespace: true + rule: lessThan + value: 0 + relativeDistanceType: longitudinal + coordinateSystem: lane + routingAlgorithm: undefined + TimeToCollisionConditionTarget: + EntityRef: + entityRef: vehicle_01 + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: [ entityRef: ego ] + EntityCondition: + TimeToCollisionCondition: + freespace: false + rule: lessThan + value: 0 + relativeDistanceType: cartesianDistance + coordinateSystem: entity + routingAlgorithm: undefined + TimeToCollisionConditionTarget: + EntityRef: + entityRef: vehicle_01 + Action: + - name: '' + UserDefinedAction: + CustomCommandAction: + type: exitFailure + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 0 + rule: greaterThan + StopTrigger: + ConditionGroup: [] From ec0bea7bf55eca3ec550ae55e133b959cbcb40d3 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 26 Nov 2024 14:33:32 +0900 Subject: [PATCH 19/25] Cleanup static member function `TimeToCollisionCondition::evaluate` Signed-off-by: yamacir-kit --- .../simulator_core.hpp | 169 +++++++++--------- .../syntax/time_to_collision_condition.hpp | 75 ++++---- ...ityCondition.TimeToCollisionCondition.yaml | 79 +++++++- 3 files changed, 190 insertions(+), 133 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index 628c7a9c6a4..0b440c48199 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -531,90 +531,6 @@ class SimulatorCore return core->getCurrentAccel(std::forward(xs)...).linear.x; } - static auto evaluateCartesianTimeToCollisionCondition(const Entity & from, const Entity & to) - { - if (const auto entity_a = core->getEntity(from.name())) { - if (const auto entity_b = core->getEntity(to.name())) { - struct OrientedBoundingBox - { - Eigen::Vector3d position; - - Eigen::Matrix3d rotation; - - Eigen::Vector3d size; // [width, height, depth] - - explicit OrientedBoundingBox( - const geometry_msgs::msg::Pose & pose, - const traffic_simulator_msgs::msg::BoundingBox & box) - : position( - pose.position.x + box.center.x, pose.position.y + box.center.y, - pose.position.z + box.center.z), - rotation(math::geometry::getRotationMatrix(pose.orientation)), - size(box.dimensions.y / 2, box.dimensions.z / 2, box.dimensions.x / 2) - { - } - - auto axis(std::size_t index) const -> Eigen::Vector3d { return rotation.col(index); } - }; - - const Eigen::Vector3d v = [&]() { - const auto v = evaluateRelativeSpeed(from, to); - return Eigen::Vector3d(v.x, v.y, v.z); - }(); - - const auto a = OrientedBoundingBox(entity_a->getMapPose(), entity_a->getBoundingBox()); - const auto b = OrientedBoundingBox(entity_b->getMapPose(), entity_b->getBoundingBox()); - - const auto axes = std::array{ - a.axis(0), - b.axis(0), - - a.axis(1), - b.axis(1), - - a.axis(2), - b.axis(2), - - a.axis(0).cross(b.axis(0)), - a.axis(0).cross(b.axis(1)), - a.axis(0).cross(b.axis(2)), - - a.axis(1).cross(b.axis(0)), - a.axis(1).cross(b.axis(1)), - a.axis(1).cross(b.axis(2)), - - a.axis(2).cross(b.axis(0)), - a.axis(2).cross(b.axis(1)), - a.axis(2).cross(b.axis(2)), - }; - - auto t_min = std::numeric_limits::infinity(); - - Eigen::Vector3d d = b.position - a.position; - - for (const auto & axis : axes) { - auto project = [&](const auto & obb) { - return std::abs(axis.dot(obb.axis(0)) * obb.size(0)) + - std::abs(axis.dot(obb.axis(1)) * obb.size(1)) + - std::abs(axis.dot(obb.axis(2)) * obb.size(2)); - }; - - if (const auto relative_speed = v.dot(axis); relative_speed < 0) { - const auto separation = std::abs(d.dot(axis)) - project(a) - project(b); - - if (const auto t = separation / -relative_speed; 0 < t) { - t_min = std::min(t_min, t); - } - } - } - - return t_min; - } - } - - return std::numeric_limits::quiet_NaN(); - } - template static auto evaluateCollisionCondition(Ts &&... xs) -> bool { @@ -639,7 +555,6 @@ class SimulatorCore } static auto evaluateRelativeSpeed(const Entity & from, const Entity & to) - -> geometry_msgs::msg::Vector3 { auto direction = [](auto orientation) { const auto euler_angle = math::geometry::convertQuaternionToEulerAngle(orientation); @@ -707,6 +622,90 @@ class SimulatorCore return std::numeric_limits::quiet_NaN(); } } + + static auto evaluateTimeToCollisionCondition(const Entity & from, const Entity & to) + { + if (const auto entity_a = core->getEntity(from.name())) { + if (const auto entity_b = core->getEntity(to.name())) { + struct OrientedBoundingBox + { + Eigen::Vector3d position; + + Eigen::Matrix3d rotation; + + Eigen::Vector3d size; // [width, height, depth] + + explicit OrientedBoundingBox( + const geometry_msgs::msg::Pose & pose, + const traffic_simulator_msgs::msg::BoundingBox & box) + : position( + pose.position.x + box.center.x, pose.position.y + box.center.y, + pose.position.z + box.center.z), + rotation(math::geometry::getRotationMatrix(pose.orientation)), + size(box.dimensions.y / 2, box.dimensions.z / 2, box.dimensions.x / 2) + { + } + + auto axis(std::size_t index) const -> Eigen::Vector3d { return rotation.col(index); } + }; + + const Eigen::Vector3d v = [&]() { + const auto v = evaluateRelativeSpeed(from, to); + return Eigen::Vector3d(v.x, v.y, v.z); + }(); + + const auto a = OrientedBoundingBox(entity_a->getMapPose(), entity_a->getBoundingBox()); + const auto b = OrientedBoundingBox(entity_b->getMapPose(), entity_b->getBoundingBox()); + + const auto axes = std::array{ + a.axis(0), + b.axis(0), + + a.axis(1), + b.axis(1), + + a.axis(2), + b.axis(2), + + a.axis(0).cross(b.axis(0)), + a.axis(0).cross(b.axis(1)), + a.axis(0).cross(b.axis(2)), + + a.axis(1).cross(b.axis(0)), + a.axis(1).cross(b.axis(1)), + a.axis(1).cross(b.axis(2)), + + a.axis(2).cross(b.axis(0)), + a.axis(2).cross(b.axis(1)), + a.axis(2).cross(b.axis(2)), + }; + + auto t_min = std::numeric_limits::infinity(); + + Eigen::Vector3d d = b.position - a.position; + + for (const auto & axis : axes) { + auto project = [&](const auto & obb) { + return std::abs(axis.dot(obb.axis(0)) * obb.size(0)) + + std::abs(axis.dot(obb.axis(1)) * obb.size(1)) + + std::abs(axis.dot(obb.axis(2)) * obb.size(2)); + }; + + if (const auto relative_speed = v.dot(axis); relative_speed < 0) { + const auto separation = std::abs(d.dot(axis)) - project(a) - project(b); + + if (const auto t = separation / -relative_speed; 0 < t) { + t_min = std::min(t_min, t); + } + } + } + + return t_min; + } + } + + return std::numeric_limits::quiet_NaN(); + } }; class NonStandardOperation : private CoordinateSystemConversion diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp index 087822fd67d..dd606281e7d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -135,55 +135,44 @@ struct TimeToCollisionCondition : private Scope, private SimulatorCore::Conditio } }; - auto speed = [&](auto &&... xs) { + auto directional_dimension = [&]() { + switch (relative_distance_type) { + case RelativeDistanceType::longitudinal: + return std::optional(DirectionalDimension::longitudinal); + case RelativeDistanceType::lateral: + return std::optional(DirectionalDimension::lateral); + default: + case RelativeDistanceType::euclidianDistance: + return std::optional(std::nullopt); + }; + }; + + auto speed = [&]() { if (time_to_collision_condition_target.is()) { return RelativeSpeedCondition::evaluate( - entities, // - triggering_entity, // - time_to_collision_condition_target.as(), std::forward(xs)...); + entities, triggering_entity, time_to_collision_condition_target.as(), + directional_dimension()); } else { - return SpeedCondition::evaluate( - entities, triggering_entity, std::forward(xs)...); + return SpeedCondition::evaluate(entities, triggering_entity, directional_dimension()); } }; - switch (relative_distance_type) { - case RelativeDistanceType::longitudinal: - /* - There is no need to treat the cases where the speed is zero, NaN, or - infinity specially. When zero, NaN, or infinity appear in the - denominator, the Time-To-Collision will be infinity, NaN, or zero, - respectively, which are the desired return values to distinguish - between "no collision after infinite time", "undefined", and - "already a collision". - */ - return distance() / speed(DirectionalDimension::longitudinal); - - case RelativeDistanceType::lateral: - /* - There is no need to treat the cases where the speed is zero, NaN, or - infinity specially. When zero, NaN, or infinity appear in the - denominator, the Time-To-Collision will be infinity, NaN, or zero, - respectively, which are the desired return values to distinguish - between "no collision after infinite time", "undefined", and - "already a collision". - */ - return distance() / speed(DirectionalDimension::lateral); - - default: - case RelativeDistanceType::euclidianDistance: - if (time_to_collision_condition_target.is()) { - if (freespace) { - return evaluateCartesianTimeToCollisionCondition( - triggering_entity, time_to_collision_condition_target.as()); - } else { - // TODO - return std::numeric_limits::quiet_NaN(); - } - } else { - // TODO - return distance() / speed(std::nullopt); - } + if ( + time_to_collision_condition_target.is() and + coordinate_system == CoordinateSystem::entity and + relative_distance_type == RelativeDistanceType::euclidianDistance and freespace) { + return evaluateTimeToCollisionCondition( + triggering_entity, time_to_collision_condition_target.as()); + } else { + /* + There is no need to treat the cases where the speed is zero, NaN, or + infinity specially. When zero, NaN, or infinity appear in the + denominator, the Time-To-Collision will be infinity, NaN, or zero, + respectively, which are the desired return values to distinguish + between "no collision after infinite time", "undefined", and "already + a collision". + */ + return distance() / speed(); } } diff --git a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml index da9326acb0f..f5de56f82df 100644 --- a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml +++ b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml @@ -106,10 +106,21 @@ OpenSCENARIO: - name: '' delay: 0 conditionEdge: none - ByValueCondition: - SimulationTimeCondition: - value: 180 - rule: greaterThan + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: [ entityRef: ego ] + EntityCondition: + TimeToCollisionCondition: + freespace: true + rule: lessThan + value: 0 + relativeDistanceType: longitudinal + coordinateSystem: lane + routingAlgorithm: undefined + TimeToCollisionConditionTarget: + EntityRef: + entityRef: vehicle_01 - Condition: - name: '' delay: 0 @@ -120,7 +131,7 @@ OpenSCENARIO: EntityRef: [ entityRef: ego ] EntityCondition: TimeToCollisionCondition: - freespace: true + freespace: false rule: lessThan value: 0 relativeDistanceType: longitudinal @@ -129,6 +140,64 @@ OpenSCENARIO: TimeToCollisionConditionTarget: EntityRef: entityRef: vehicle_01 + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: [ entityRef: ego ] + EntityCondition: + TimeToCollisionCondition: + freespace: true + rule: lessThan + value: 0 + relativeDistanceType: longitudinal + coordinateSystem: entity + routingAlgorithm: undefined + TimeToCollisionConditionTarget: + EntityRef: + entityRef: vehicle_01 + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: [ entityRef: ego ] + EntityCondition: + TimeToCollisionCondition: + freespace: false + rule: lessThan + value: 0 + relativeDistanceType: longitudinal + coordinateSystem: entity + routingAlgorithm: undefined + TimeToCollisionConditionTarget: + EntityRef: + entityRef: vehicle_01 + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: [ entityRef: ego ] + EntityCondition: + TimeToCollisionCondition: + freespace: true + rule: lessThan + value: 0 + relativeDistanceType: cartesianDistance + coordinateSystem: entity + routingAlgorithm: undefined + TimeToCollisionConditionTarget: + EntityRef: + entityRef: vehicle_01 + - Condition: - name: '' delay: 0 conditionEdge: none From 64da48270d347f71a5f44a9c55c4085ea9d6e1bf Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 26 Nov 2024 15:07:40 +0900 Subject: [PATCH 20/25] Fix `TimeToCollisionCondition` to return inf if relative speed < zero Signed-off-by: yamacir-kit --- .../syntax/time_to_collision_condition.hpp | 10 +--------- ...ition.EntityCondition.TimeToCollisionCondition.yaml | 2 +- 2 files changed, 2 insertions(+), 10 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp index dd606281e7d..681e1045bfb 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -164,15 +164,7 @@ struct TimeToCollisionCondition : private Scope, private SimulatorCore::Conditio return evaluateTimeToCollisionCondition( triggering_entity, time_to_collision_condition_target.as()); } else { - /* - There is no need to treat the cases where the speed is zero, NaN, or - infinity specially. When zero, NaN, or infinity appear in the - denominator, the Time-To-Collision will be infinity, NaN, or zero, - respectively, which are the desired return values to distinguish - between "no collision after infinite time", "undefined", and "already - a collision". - */ - return distance() / speed(); + return distance() / std::max(speed(), 0.0); } } diff --git a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml index f5de56f82df..640fc08fc46 100644 --- a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml +++ b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml @@ -64,7 +64,7 @@ OpenSCENARIO: Properties: Property: - name: maxSpeed - value: '1' + value: '0.5' Story: - name: '' Act: From 4f2863a5ba42d7f2fd09d61b9396feb8b044127e Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 26 Nov 2024 19:50:31 +0900 Subject: [PATCH 21/25] Fix `evaluateTimeToCollisionCondition` to not return meaningless value when collisions cannot occur Signed-off-by: yamacir-kit --- .../simulator_core.hpp | 96 +++++++++++++++---- ...ityCondition.TimeToCollisionCondition.yaml | 58 ++++++++++- 2 files changed, 133 insertions(+), 21 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index 0b440c48199..795f44377af 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -625,6 +625,19 @@ class SimulatorCore static auto evaluateTimeToCollisionCondition(const Entity & from, const Entity & to) { + /* + This function uses the Separating Axis Theorem (SAT) to find the + Time-To-Collision (TTC) of two entities in the world coordinate + system. + + First, the expected time of collision is obtained independently for + each separating axis. Then, we check whether the polygons of the + entities actually collide after that time. If no collision occurs, the + expected collision time is rejected. The lowest value of the expected + collision times obtained for each separate axis is then returned as + the TTC. + */ + if (const auto entity_a = core->getEntity(from.name())) { if (const auto entity_b = core->getEntity(to.name())) { struct OrientedBoundingBox @@ -659,12 +672,11 @@ class SimulatorCore const auto axes = std::array{ a.axis(0), - b.axis(0), - a.axis(1), - b.axis(1), - a.axis(2), + + b.axis(0), + b.axis(1), b.axis(2), a.axis(0).cross(b.axis(0)), @@ -680,22 +692,74 @@ class SimulatorCore a.axis(2).cross(b.axis(2)), }; - auto t_min = std::numeric_limits::infinity(); - Eigen::Vector3d d = b.position - a.position; - for (const auto & axis : axes) { - auto project = [&](const auto & obb) { - return std::abs(axis.dot(obb.axis(0)) * obb.size(0)) + - std::abs(axis.dot(obb.axis(1)) * obb.size(1)) + - std::abs(axis.dot(obb.axis(2)) * obb.size(2)); - }; + auto t_min = std::numeric_limits::infinity(); - if (const auto relative_speed = v.dot(axis); relative_speed < 0) { - const auto separation = std::abs(d.dot(axis)) - project(a) - project(b); + auto projection = [&](const auto & box, const auto & axis) { + return std::abs(axis.dot(box.axis(0)) * box.size(0)) + + std::abs(axis.dot(box.axis(1)) * box.size(1)) + + std::abs(axis.dot(box.axis(2)) * box.size(2)); + }; - if (const auto t = separation / -relative_speed; 0 < t) { - t_min = std::min(t_min, t); + for (const auto & axis : axes) { + /* + The variable `separation` means how far apart two Oriented + Bounding Boxes (OBBs) are on the separation axis. When it is + positive, it means they are separated by `separation`, i.e. the + OBBs do not overlap on the separation axis. When it is less than + zero, it means the OBBs overlap on the separation axis. + + d.dot(axis) is the projection of the center distance between the + two OBBs onto the separation axis, and projection(a, axis) and + projection(b, axis) are half the projected range of the boxes + when the two OBBs are projected onto the separation axis. + */ + if (const auto separation = + std::abs(d.dot(axis)) - projection(a, axis) - projection(b, axis); + 0 < separation) { + /* + v.dot(axis) is the projection of the relative distance onto + the separation axis. In other words, we want to find the TTC + for each separation axis. The relative velocity is the + velocity vector of the observed object measured in the + observer's rest frame, so a negative value means that the two + OBBs are approaching each other. + */ + if (const auto relative_speed = v.dot(axis); relative_speed < 0) { + /* + Since this t is only a Time-To-Collision on this separation + axis, it is necessary to check that a and b are not + separated on all separation axes after t seconds. + */ + const auto t = separation / -relative_speed; + + const auto a_t = a; + + const auto b_t = [&]() { + /* + Since t is the exact time when contact occurs, it may not + be possible to say that a and b are in collision after t + seconds. Therefore, 0.01 seconds is added to t so that + collision can be expected to occur with certainty. This + value "0.01" has no technical basis and is an arbitrary + value. + */ + constexpr auto tolerance = 0.01; + auto copy = b; + copy.position += v * (t + tolerance); + return copy; + }(); + + Eigen::Vector3d d_t = b_t.position - a_t.position; + + if (std::all_of(axes.begin(), axes.end(), [&](const auto & axis) { + const auto separation_t = + std::abs(d_t.dot(axis)) - projection(a_t, axis) - projection(b_t, axis); + return separation_t <= 0; + })) { + t_min = std::min(t_min, t); + } } } } diff --git a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml index 640fc08fc46..555aad18bad 100644 --- a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml +++ b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml @@ -25,6 +25,13 @@ OpenSCENARIO: name: '' Properties: Property: [] + - name: vehicle_02 + CatalogReference: { catalogName: sample_vehicle, entryName: sample_vehicle } + ObjectController: + Controller: + name: '' + Properties: + Property: [] Storyboard: Init: Actions: @@ -35,8 +42,8 @@ OpenSCENARIO: Position: LanePosition: roadId: '' - laneId: '34513' - s: 5 + laneId: '34976' + s: 10 offset: 0 Orientation: type: relative @@ -49,8 +56,8 @@ OpenSCENARIO: Position: LanePosition: roadId: '' - laneId: '34510' - s: 10 + laneId: '34579' + s: 0 offset: 0 Orientation: type: relative @@ -65,6 +72,28 @@ OpenSCENARIO: Property: - name: maxSpeed value: '0.5' + - entityRef: vehicle_02 + PrivateAction: + - TeleportAction: + Position: + LanePosition: + roadId: '' + laneId: '34576' + s: 0 + offset: 0 + Orientation: + type: relative + h: 0 + p: 0 + r: 0 + - ControllerAction: + AssignControllerAction: + Controller: + name: '' + Properties: + Property: + - name: maxSpeed + value: '2' # If 2.5, collision will occur. Story: - name: '' Act: @@ -89,7 +118,7 @@ OpenSCENARIO: conditionEdge: none ByValueCondition: SimulationTimeCondition: - value: 20 + value: 30 rule: greaterThan Action: - name: '' @@ -216,6 +245,25 @@ OpenSCENARIO: TimeToCollisionConditionTarget: EntityRef: entityRef: vehicle_01 + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: [ entityRef: ego ] + EntityCondition: + TimeToCollisionCondition: + freespace: true + rule: lessThan + value: 0 + relativeDistanceType: cartesianDistance + coordinateSystem: entity + routingAlgorithm: undefined + TimeToCollisionConditionTarget: + EntityRef: + entityRef: vehicle_02 Action: - name: '' UserDefinedAction: From d524164dd48559fcaac0fe0e0ad9f920ccbdccdb Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Mon, 9 Dec 2024 16:33:34 +0900 Subject: [PATCH 22/25] Cleanup Signed-off-by: yamacir-kit --- .../geometry/include/geometry/vector3/norm.hpp | 1 - .../openscenario_interpreter/simulator_core.hpp | 12 ++---------- .../syntax/time_to_collision_condition.hpp | 14 ++++++++++---- .../syntax/time_to_collision_condition_target.hpp | 2 +- .../src/syntax/add_entity_action.cpp | 2 +- .../src/syntax/speed_condition.cpp | 2 -- 6 files changed, 14 insertions(+), 19 deletions(-) diff --git a/common/math/geometry/include/geometry/vector3/norm.hpp b/common/math/geometry/include/geometry/vector3/norm.hpp index 6746c7ec7c6..44fa57c9e62 100644 --- a/common/math/geometry/include/geometry/vector3/norm.hpp +++ b/common/math/geometry/include/geometry/vector3/norm.hpp @@ -15,7 +15,6 @@ #ifndef GEOMETRY__VECTOR3__NORM_HPP_ #define GEOMETRY__VECTOR3__NORM_HPP_ -#include #include namespace math diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index 82e3e2a0623..1e53a012a36 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -17,8 +17,6 @@ #include #include -#include -#include #include #include #include @@ -564,15 +562,9 @@ class SimulatorCore if (const auto observer = core->getEntity(from.name())) { if (const auto observed = core->getEntity(to.name())) { auto velocity = [](const auto & entity) -> Eigen::Vector3d { - auto direction = [](auto orientation) -> Eigen::Vector3d { - const auto euler_angle = math::geometry::convertQuaternionToEulerAngle(orientation); - const auto r = euler_angle.x; - const auto p = euler_angle.y; - const auto y = euler_angle.z; - return Eigen::Vector3d( - std::cos(y) * std::cos(p), std::sin(y) * std::cos(p), std::sin(p)); + 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; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp index 681e1045bfb..17a34204c03 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -29,7 +29,7 @@ namespace openscenario_interpreter inline namespace syntax { /* - TimeToCollisionCondition (OpenSCENARIO XML 1.3) + TimeToCollisionCondition (OpenSCENARIO XML 1.3.1) The currently predicted time to collision of a triggering entity/entities and either a reference entity or an explicit position is compared to a given @@ -106,9 +106,15 @@ struct TimeToCollisionCondition : private Scope, private SimulatorCore::Conditio { auto description = std::stringstream(); - description << triggering_entities.description() << "'s time to collision to given entity " - << "TODO-RELATIVE-DISTANCE-TARGET" - << " = "; + description << triggering_entities.description() << "'s time-to-collision to given "; + + if (time_to_collision_condition_target.is()) { + description << " entity " << time_to_collision_condition_target.as(); + } else { + description << " position"; + } + + description << " = "; print_to(description, evaluations); diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition_target.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition_target.hpp index ac1b051008a..8e15f1f6f3c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition_target.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition_target.hpp @@ -23,7 +23,7 @@ namespace openscenario_interpreter inline namespace syntax { /* - TimeToCollisionConditionTarget 1.3 + TimeToCollisionConditionTarget (OpenSCENARIO XML 1.3.1) Target position used in the TimeToCollisionCondition. Can be defined as either an explicit position, or the position of a reference entity. diff --git a/openscenario/openscenario_interpreter/src/syntax/add_entity_action.cpp b/openscenario/openscenario_interpreter/src/syntax/add_entity_action.cpp index ae11d05f50c..d0408597bf5 100644 --- a/openscenario/openscenario_interpreter/src/syntax/add_entity_action.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/add_entity_action.cpp @@ -47,7 +47,7 @@ auto AddEntityAction::endsImmediately() noexcept -> bool // auto AddEntityAction::operator()(const EntityRef & entity_ref) const -> void try { - const auto entity = global().entities->ref(entity_ref); + const auto entity = global().entities->at(entity_ref); const auto add_entity = overload( [&](const Vehicle & vehicle) { diff --git a/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp index 8d994c6f14f..cc8d64b0c41 100644 --- a/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp @@ -12,9 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include #include -#include #include #include #include From ab76fb074f6cc1028b8172df8acc6e5a5595b75a Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 10 Dec 2024 13:46:24 +0900 Subject: [PATCH 23/25] Update document `OpenSCENARIOSupport.md` Signed-off-by: yamacir-kit --- docs/developer_guide/OpenSCENARIOSupport.md | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/docs/developer_guide/OpenSCENARIOSupport.md b/docs/developer_guide/OpenSCENARIOSupport.md index 2f64a14c51c..d8821dd97da 100644 --- a/docs/developer_guide/OpenSCENARIOSupport.md +++ b/docs/developer_guide/OpenSCENARIOSupport.md @@ -486,8 +486,8 @@ Currently, the only way to know the result of the simulation is by viewing the s | TimeOfDay | 1.3 | | | TimeOfDayCondition | unimplemented | | | TimeReference | 1.3 | | -| TimeToCollisionCondition | unimplemented | | -| TimeToCollisionConditionTarget | unimplemented | | +| TimeToCollisionCondition | 1.3.1 (partial) | [detail](#TimeToCollisionCondition) | +| TimeToCollisionConditionTarget | 1.3.1 | | | Timing | 1.3 | | | TrafficAction | unimplemented | | | TrafficArea | unimplemented | | @@ -848,6 +848,13 @@ Currently, the only way to know the result of the simulation is by viewing the s - Property `freespace` is ignored. - The simulator behaves as if `freespace` is `false`. +#### TimeToCollisionCondition + +- Since `TimeToCollisionCondition` is implemented using `DistanceCondition`, + `RelativeDistanceCondition`, `SpeedCondition`, and `RelativeSpeedCondition`, + if a combination of properties that is not supported by those Conditions is + given to `TimeToCollisionCondition`, an error will be thrown. + #### TransitionDynamics - Property `followingMode` created in version 1.2 is ignored. From b2a1b1e715950c69594b9d8cae40944a6c27ab8b Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 12 Dec 2024 12:00:03 +0900 Subject: [PATCH 24/25] Remove static member function `evaluateTimeToCollisionCondition` Signed-off-by: yamacir-kit --- .../simulator_core.hpp | 145 ------------------ .../syntax/time_to_collision_condition.hpp | 33 ++-- ...ityCondition.TimeToCollisionCondition.yaml | 48 ------ 3 files changed, 12 insertions(+), 214 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index 8bf5f664b3b..5252176abfc 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -620,151 +620,6 @@ class SimulatorCore return std::numeric_limits::quiet_NaN(); } } - - static auto evaluateTimeToCollisionCondition(const Entity & from, const Entity & to) - { - /* - This function uses the Separating Axis Theorem (SAT) to find the - Time-To-Collision (TTC) of two entities in the world coordinate - system. - - First, the expected time of collision is obtained independently for - each separating axis. Then, we check whether the polygons of the - entities actually collide after that time. If no collision occurs, the - expected collision time is rejected. The lowest value of the expected - collision times obtained for each separate axis is then returned as - the TTC. - */ - - if (const auto entity_a = core->getEntity(from.name())) { - if (const auto entity_b = core->getEntity(to.name())) { - struct OrientedBoundingBox - { - Eigen::Vector3d position; - - Eigen::Matrix3d rotation; - - Eigen::Vector3d size; // [width, height, depth] - - explicit OrientedBoundingBox( - const geometry_msgs::msg::Pose & pose, - const traffic_simulator_msgs::msg::BoundingBox & box) - : position( - pose.position.x + box.center.x, pose.position.y + box.center.y, - pose.position.z + box.center.z), - rotation(math::geometry::getRotationMatrix(pose.orientation)), - size(box.dimensions.y / 2, box.dimensions.z / 2, box.dimensions.x / 2) - { - } - - auto axis(std::size_t index) const -> Eigen::Vector3d { return rotation.col(index); } - }; - - const Eigen::Vector3d v = evaluateRelativeSpeed(from, to); - - const auto a = OrientedBoundingBox(entity_a->getMapPose(), entity_a->getBoundingBox()); - const auto b = OrientedBoundingBox(entity_b->getMapPose(), entity_b->getBoundingBox()); - - const auto axes = std::array{ - a.axis(0), - a.axis(1), - a.axis(2), - - b.axis(0), - b.axis(1), - b.axis(2), - - a.axis(0).cross(b.axis(0)), - a.axis(0).cross(b.axis(1)), - a.axis(0).cross(b.axis(2)), - - a.axis(1).cross(b.axis(0)), - a.axis(1).cross(b.axis(1)), - a.axis(1).cross(b.axis(2)), - - a.axis(2).cross(b.axis(0)), - a.axis(2).cross(b.axis(1)), - a.axis(2).cross(b.axis(2)), - }; - - Eigen::Vector3d d = b.position - a.position; - - auto t_min = std::numeric_limits::infinity(); - - auto projection = [&](const auto & box, const auto & axis) { - return std::abs(axis.dot(box.axis(0)) * box.size(0)) + - std::abs(axis.dot(box.axis(1)) * box.size(1)) + - std::abs(axis.dot(box.axis(2)) * box.size(2)); - }; - - for (const auto & axis : axes) { - /* - The variable `separation` means how far apart two Oriented - Bounding Boxes (OBBs) are on the separation axis. When it is - positive, it means they are separated by `separation`, i.e. the - OBBs do not overlap on the separation axis. When it is less than - zero, it means the OBBs overlap on the separation axis. - - d.dot(axis) is the projection of the center distance between the - two OBBs onto the separation axis, and projection(a, axis) and - projection(b, axis) are half the projected range of the boxes - when the two OBBs are projected onto the separation axis. - */ - if (const auto separation = - std::abs(d.dot(axis)) - projection(a, axis) - projection(b, axis); - 0 < separation) { - /* - v.dot(axis) is the projection of the relative distance onto - the separation axis. In other words, we want to find the TTC - for each separation axis. The relative velocity is the - velocity vector of the observed object measured in the - observer's rest frame, so a negative value means that the two - OBBs are approaching each other. - */ - if (const auto relative_speed = v.dot(axis); relative_speed < 0) { - /* - Since this t is only a Time-To-Collision on this separation - axis, it is necessary to check that a and b are not - separated on all separation axes after t seconds. - */ - const auto t = separation / -relative_speed; - - const auto a_t = a; - - const auto b_t = [&]() { - /* - Since t is the exact time when contact occurs, it may not - be possible to say that a and b are in collision after t - seconds. Therefore, 0.01 seconds is added to t so that - collision can be expected to occur with certainty. This - value "0.01" has no technical basis and is an arbitrary - value. - */ - constexpr auto tolerance = 0.01; - auto copy = b; - copy.position += v * (t + tolerance); - return copy; - }(); - - Eigen::Vector3d d_t = b_t.position - a_t.position; - - if (std::all_of(axes.begin(), axes.end(), [&](const auto & axis) { - const auto separation_t = - std::abs(d_t.dot(axis)) - projection(a_t, axis) - projection(b_t, axis); - return separation_t <= 0; - })) { - t_min = std::min(t_min, t); - } - } - } - } - - return t_min; - } - } - - return std::numeric_limits::quiet_NaN(); - } }; class NonStandardOperation : private CoordinateSystemConversion diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp index 17a34204c03..ff290830df5 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -141,19 +141,18 @@ struct TimeToCollisionCondition : private Scope, private SimulatorCore::Conditio } }; - auto directional_dimension = [&]() { - switch (relative_distance_type) { - case RelativeDistanceType::longitudinal: - return std::optional(DirectionalDimension::longitudinal); - case RelativeDistanceType::lateral: - return std::optional(DirectionalDimension::lateral); - default: - case RelativeDistanceType::euclidianDistance: - return std::optional(std::nullopt); - }; - }; - auto speed = [&]() { + auto directional_dimension = [&]() { + switch (relative_distance_type) { + case RelativeDistanceType::longitudinal: + return std::optional(DirectionalDimension::longitudinal); + case RelativeDistanceType::lateral: + return std::optional(DirectionalDimension::lateral); + default: + case RelativeDistanceType::euclidianDistance: + return std::optional(std::nullopt); + }; + }; if (time_to_collision_condition_target.is()) { return RelativeSpeedCondition::evaluate( entities, triggering_entity, time_to_collision_condition_target.as(), @@ -163,15 +162,7 @@ struct TimeToCollisionCondition : private Scope, private SimulatorCore::Conditio } }; - if ( - time_to_collision_condition_target.is() and - coordinate_system == CoordinateSystem::entity and - relative_distance_type == RelativeDistanceType::euclidianDistance and freespace) { - return evaluateTimeToCollisionCondition( - triggering_entity, time_to_collision_condition_target.as()); - } else { - return distance() / std::max(speed(), 0.0); - } + return distance() / std::max(speed(), 0.0); } auto evaluate() diff --git a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml index 555aad18bad..213ac429acd 100644 --- a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml +++ b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.TimeToCollisionCondition.yaml @@ -25,13 +25,6 @@ OpenSCENARIO: name: '' Properties: Property: [] - - name: vehicle_02 - CatalogReference: { catalogName: sample_vehicle, entryName: sample_vehicle } - ObjectController: - Controller: - name: '' - Properties: - Property: [] Storyboard: Init: Actions: @@ -72,28 +65,6 @@ OpenSCENARIO: Property: - name: maxSpeed value: '0.5' - - entityRef: vehicle_02 - PrivateAction: - - TeleportAction: - Position: - LanePosition: - roadId: '' - laneId: '34576' - s: 0 - offset: 0 - Orientation: - type: relative - h: 0 - p: 0 - r: 0 - - ControllerAction: - AssignControllerAction: - Controller: - name: '' - Properties: - Property: - - name: maxSpeed - value: '2' # If 2.5, collision will occur. Story: - name: '' Act: @@ -245,25 +216,6 @@ OpenSCENARIO: TimeToCollisionConditionTarget: EntityRef: entityRef: vehicle_01 - - Condition: - - name: '' - delay: 0 - conditionEdge: none - ByEntityCondition: - TriggeringEntities: - triggeringEntitiesRule: any - EntityRef: [ entityRef: ego ] - EntityCondition: - TimeToCollisionCondition: - freespace: true - rule: lessThan - value: 0 - relativeDistanceType: cartesianDistance - coordinateSystem: entity - routingAlgorithm: undefined - TimeToCollisionConditionTarget: - EntityRef: - entityRef: vehicle_02 Action: - name: '' UserDefinedAction: From 1717315cebb72362ba915681735b595956c1c1b5 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 13 Dec 2024 14:14:46 +0900 Subject: [PATCH 25/25] Update `TimeToCollisionCondition` to call `SpeedCondition` in standard compatible mode Signed-off-by: yamacir-kit --- .../syntax/time_to_collision_condition.hpp | 3 ++- .../scenario_test_runner/scenario/sample.yaml | 13 ++----------- 2 files changed, 4 insertions(+), 12 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp index ff290830df5..3dc68ba3cd9 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/time_to_collision_condition.hpp @@ -158,7 +158,8 @@ struct TimeToCollisionCondition : private Scope, private SimulatorCore::Conditio entities, triggering_entity, time_to_collision_condition_target.as(), directional_dimension()); } else { - return SpeedCondition::evaluate(entities, triggering_entity, directional_dimension()); + return SpeedCondition::evaluate( + entities, triggering_entity, directional_dimension(), Compatibility::standard); } }; diff --git a/test_runner/scenario_test_runner/scenario/sample.yaml b/test_runner/scenario_test_runner/scenario/sample.yaml index d465b19c270..37d6440f158 100644 --- a/test_runner/scenario_test_runner/scenario/sample.yaml +++ b/test_runner/scenario_test_runner/scenario/sample.yaml @@ -10,16 +10,7 @@ OpenSCENARIO: revMajor: 1 revMinor: 0 ParameterDeclarations: - ParameterDeclaration: - - name: random_offset - parameterType: double - value: $(ros2 run openscenario_interpreter_example uniform_distribution -1.0 1.0) - ConstraintGroup: - - ValueConstraint: - - rule: lessOrEqual - value: 1.0 - - rule: greaterOrEqual - value: -1.0 + ParameterDeclaration: [] CatalogLocations: VehicleCatalog: Directory: @@ -54,7 +45,7 @@ OpenSCENARIO: roadId: '' laneId: LANE_ID s: 1 - offset: $random_offset + offset: 0 Orientation: type: relative h: 0