From 1abe1bda84869f381d0d3b6f5b64e8e7bd5636cc Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 21 May 2024 15:05:48 +0900 Subject: [PATCH 01/54] 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/54] 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/54] 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/54] 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/54] 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/54] 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/54] 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/54] 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/54] 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/54] 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/54] 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/54] 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/54] 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/54] 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/54] 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 b67579782898863834858c6a1acc26ceb5e98928 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Mon, 11 Nov 2024 12:16:28 +0900 Subject: [PATCH 16/54] Add launch argument `simulate_localization` to `scenario_test_runner` Signed-off-by: yamacir-kit --- .../include/concealer/autoware_universe.hpp | 3 +- external/concealer/src/autoware_universe.cpp | 31 +++++++++++++++++-- .../ego_entity_simulation.cpp | 3 +- .../src/entity/ego_entity.cpp | 1 + .../launch/scenario_test_runner.launch.py | 4 +++ 5 files changed, 37 insertions(+), 5 deletions(-) diff --git a/external/concealer/include/concealer/autoware_universe.hpp b/external/concealer/include/concealer/autoware_universe.hpp index 39d4b3f576b..01067a3f7f3 100644 --- a/external/concealer/include/concealer/autoware_universe.hpp +++ b/external/concealer/include/concealer/autoware_universe.hpp @@ -44,6 +44,7 @@ class AutowareUniverse : public Autoware PublisherWrapper setAcceleration; PublisherWrapper setOdometry; + PublisherWrapper setPose; PublisherWrapper setSteeringReport; PublisherWrapper setGearReport; PublisherWrapper setControlModeReport; @@ -69,7 +70,7 @@ class AutowareUniverse : public Autoware auto stopAndJoin() -> void; public: - CONCEALER_PUBLIC explicit AutowareUniverse(); + CONCEALER_PUBLIC explicit AutowareUniverse(bool); ~AutowareUniverse(); diff --git a/external/concealer/src/autoware_universe.cpp b/external/concealer/src/autoware_universe.cpp index b22f2c68c9b..4fc18db8ff8 100644 --- a/external/concealer/src/autoware_universe.cpp +++ b/external/concealer/src/autoware_universe.cpp @@ -16,15 +16,25 @@ namespace concealer { -AutowareUniverse::AutowareUniverse() +AutowareUniverse::AutowareUniverse(bool simulate_localization) : getCommand("/control/command/control_cmd", rclcpp::QoS(1), *this), getGearCommandImpl("/control/command/gear_cmd", rclcpp::QoS(1), *this), getTurnIndicatorsCommand("/control/command/turn_indicators_cmd", rclcpp::QoS(1), *this), getPathWithLaneId( "/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id", rclcpp::QoS(1), *this), - setAcceleration("/localization/acceleration", *this), - setOdometry("/localization/kinematic_state", *this), + setAcceleration( + simulate_localization ? "/localization/acceleration" + : "/simulation/debug/localization/acceleration", + *this), + setOdometry( + simulate_localization ? "/localization/kinematic_state" + : "/simulation/debug/localization/kinematic_state", + *this), + setPose( + simulate_localization ? "/simulation/debug/localization/pose_estimator/pose_with_covariance" + : "/localization/pose_estimator/pose_with_covariance", + *this), setSteeringReport("/vehicle/status/steering_status", *this), setGearReport("/vehicle/status/gear_status", *this), setControlModeReport("/vehicle/status/control_mode", *this), @@ -102,6 +112,21 @@ auto AutowareUniverse::updateLocalization() -> void return message; }()); + setPose([this]() { + // See https://github.com/tier4/autoware.universe/blob/45ab20af979c5663e5a8d4dda787b1dea8d6e55b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp#L785-L803 + geometry_msgs::msg::PoseWithCovarianceStamped message; + message.header.stamp = get_clock()->now(); + message.header.frame_id = "map"; + message.pose.pose = current_pose.load(); + message.pose.covariance.at(6 * 0 + 0) = 0.0225; // XYZRPY_COV_IDX::X_X + message.pose.covariance.at(6 * 1 + 1) = 0.0225; // XYZRPY_COV_IDX::Y_Y + message.pose.covariance.at(6 * 2 + 2) = 0.0225; // XYZRPY_COV_IDX::Z_Z + message.pose.covariance.at(6 * 3 + 3) = 0.000625; // XYZRPY_COV_IDX::ROLL_ROLL + message.pose.covariance.at(6 * 4 + 4) = 0.000625; // XYZRPY_COV_IDX::PITCH_PITCH + message.pose.covariance.at(6 * 5 + 5) = 0.000625; // XYZRPY_COV_IDX::YAW_YAW + return message; + }()); + setTransform(current_pose.load()); } diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index 23ac33eeb3f..7ce88f75de3 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -41,7 +41,8 @@ EgoEntitySimulation::EgoEntitySimulation( const traffic_simulator_msgs::msg::VehicleParameters & parameters, double step_time, const std::shared_ptr & hdmap_utils, const rclcpp::Parameter & use_sim_time, const bool consider_acceleration_by_road_slope) -: autoware(std::make_unique()), +: autoware( + std::make_unique(getParameter("simulate_localization"))), vehicle_model_type_(getVehicleModelType()), vehicle_model_ptr_(makeSimulationModel(vehicle_model_type_, step_time, parameters)), status_(initial_status, std::nullopt), diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index 72d29a96de8..332b26723f5 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -54,6 +54,7 @@ auto EgoEntity::makeFieldOperatorApplication( parameters.push_back("use_foa:=false"); parameters.push_back("perception/enable_traffic_light:=" + std::string(architecture_type >= "awf/universe/20230906" ? "true" : "false")); parameters.push_back("use_sim_time:=" + std::string(getParameter(node_parameters, "use_sim_time", false) ? "true" : "false")); + parameters.push_back("localization_sim_mode:=" + std::string(getParameter(node_parameters, "simulate_localization") ? "api" : "pose_twist_estimator")); // clang-format on return getParameter(node_parameters, "launch_autoware", true) diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index b6cb6b9d66a..28daf6722c1 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -85,6 +85,7 @@ def launch_setup(context, *args, **kwargs): scenario = LaunchConfiguration("scenario", default=Path("/dev/null")) sensor_model = LaunchConfiguration("sensor_model", default="") sigterm_timeout = LaunchConfiguration("sigterm_timeout", default=8) + simulate_localization = LaunchConfiguration("simulate_localization", default=True) use_sim_time = LaunchConfiguration("use_sim_time", default=False) vehicle_model = LaunchConfiguration("vehicle_model", default="") # fmt: on @@ -109,6 +110,7 @@ def launch_setup(context, *args, **kwargs): print(f"scenario := {scenario.perform(context)}") print(f"sensor_model := {sensor_model.perform(context)}") print(f"sigterm_timeout := {sigterm_timeout.perform(context)}") + print(f"simulate_localization := {simulate_localization.perform(context)}") print(f"use_sim_time := {use_sim_time.perform(context)}") print(f"vehicle_model := {vehicle_model.perform(context)}") @@ -133,6 +135,7 @@ def make_parameters(): {"rviz_config": rviz_config}, {"sensor_model": sensor_model}, {"sigterm_timeout": sigterm_timeout}, + {"simulate_localization": simulate_localization}, {"use_sim_time": use_sim_time}, {"vehicle_model": vehicle_model}, ] @@ -177,6 +180,7 @@ def collect_prefixed_parameters(): DeclareLaunchArgument("scenario", default_value=scenario ), DeclareLaunchArgument("sensor_model", default_value=sensor_model ), DeclareLaunchArgument("sigterm_timeout", default_value=sigterm_timeout ), + DeclareLaunchArgument("simulate_localization", default_value=simulate_localization ), DeclareLaunchArgument("use_sim_time", default_value=use_sim_time ), DeclareLaunchArgument("vehicle_model", default_value=vehicle_model ), # fmt: on From b11ca9df169194650873861d534c0416ab96be36 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 20 Nov 2024 14:30:53 +0900 Subject: [PATCH 17/54] Add the missing semicolon Signed-off-by: yamacir-kit --- external/concealer/include/concealer/autoware_universe.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/external/concealer/include/concealer/autoware_universe.hpp b/external/concealer/include/concealer/autoware_universe.hpp index 227fa89ff40..0692c7717c0 100644 --- a/external/concealer/include/concealer/autoware_universe.hpp +++ b/external/concealer/include/concealer/autoware_universe.hpp @@ -45,7 +45,7 @@ class AutowareUniverse : public Autoware using GearCommand = autoware_vehicle_msgs::msg::GearCommand; using GearReport = autoware_vehicle_msgs::msg::GearReport; using PathWithLaneId = tier4_planning_msgs::msg::PathWithLaneId; - using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped + using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; using SteeringReport = autoware_vehicle_msgs::msg::SteeringReport; using TurnIndicatorsCommand = autoware_vehicle_msgs::msg::TurnIndicatorsCommand; using TurnIndicatorsReport = autoware_vehicle_msgs::msg::TurnIndicatorsReport; From 2656a5a38a964181b9605374fefceb3431f2b131 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 22 Nov 2024 10:35:28 +0900 Subject: [PATCH 18/54] 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 19/54] 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 20/54] 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 21/54] 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 22/54] 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 23/54] 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 e1a4989223756db2b6cd8e79d9dd5adc98d0ec85 Mon Sep 17 00:00:00 2001 From: satoshi-ota Date: Wed, 27 Nov 2024 19:36:47 +0900 Subject: [PATCH 24/54] fix(api): request enable autoware control Signed-off-by: satoshi-ota --- simulation/traffic_simulator/src/api/api.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/simulation/traffic_simulator/src/api/api.cpp b/simulation/traffic_simulator/src/api/api.cpp index 1f24e201b3c..1b8690d2ab1 100644 --- a/simulation/traffic_simulator/src/api/api.cpp +++ b/simulation/traffic_simulator/src/api/api.cpp @@ -94,6 +94,7 @@ auto API::respawn( entity_manager_ptr_->asFieldOperatorApplication(name).clearRoute(); entity_manager_ptr_->asFieldOperatorApplication(name).plan({goal_pose}); + entity_manager_ptr_->asFieldOperatorApplication(name).enableAutowareControl(); entity_manager_ptr_->asFieldOperatorApplication(name).engage(); } } From 5a94c73813d2bb854001028d8f517f1e380b6de6 Mon Sep 17 00:00:00 2001 From: satoshi-ota Date: Fri, 29 Nov 2024 10:20:11 +0900 Subject: [PATCH 25/54] fix(concealer): increase max time to request enable autoware control Signed-off-by: satoshi-ota --- .../src/field_operator_application_for_autoware_universe.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/external/concealer/src/field_operator_application_for_autoware_universe.cpp b/external/concealer/src/field_operator_application_for_autoware_universe.cpp index 072a42b628f..00bd97a1d00 100644 --- a/external/concealer/src/field_operator_application_for_autoware_universe.cpp +++ b/external/concealer/src/field_operator_application_for_autoware_universe.cpp @@ -475,7 +475,7 @@ auto FieldOperatorApplicationFor::enableAutowareControl() -> v { task_queue.delay([this]() { auto request = std::make_shared(); - requestEnableAutowareControl(request); + requestEnableAutowareControl(request, 30); }); } From d524164dd48559fcaac0fe0e0ad9f920ccbdccdb Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Mon, 9 Dec 2024 16:33:34 +0900 Subject: [PATCH 26/54] 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 b375c5fdb655b0a2f385b30ddcdc2114798ef9e2 Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Fri, 6 Dec 2024 17:20:59 +0100 Subject: [PATCH 27/54] [RJD-1369] Improve lanelet matching - 3D support - Enhanced lanelet matching algorithm (`toLaneletPose` method) by incorporating lanelet altitude. - Defined the `altitude_threshold` parameter that sets the maximum altitude difference to determine when an entity can be matched with a specific lanelet. --- .../hdmap_utils/hdmap_utils.hpp | 19 ++++++++++++++++++- .../src/hdmap_utils/hdmap_utils.cpp | 13 ++++++++++++- 2 files changed, 30 insertions(+), 2 deletions(-) diff --git a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp index 07dced38f8f..618b63b688d 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp @@ -160,7 +160,7 @@ class HdMapUtils const traffic_simulator::RoutingGraphType type = traffic_simulator::RoutingConfiguration().routing_graph_type) const -> lanelet::Ids; - auto getHeight(const traffic_simulator_msgs::msg::LaneletPose &) const -> double; + auto getAltitude(const traffic_simulator_msgs::msg::LaneletPose &) const -> double; auto getLaneChangeTrajectory( const geometry_msgs::msg::Pose & from, @@ -380,7 +380,24 @@ class HdMapUtils auto toMapPose(const traffic_simulator_msgs::msg::LaneletPose &, const bool fill_pitch = true) const -> geometry_msgs::msg::PoseStamped; + auto isAltitudeMatching(const double current_altitude, const double target_altitude) const + -> bool; + private: + /* + Using a fixed `altitude_threshold` value of 1.0 [m] is justified because the + entity's Z-position is always relative to its base. This eliminates the + need to dynamically adjust the threshold based on the entity's dimensions, + ensuring consistent altitude matching regardless of the entity type. + + The position of the entity is defined relative to its base, typically + the center of the rear axle projected onto the ground in the case of vehicles. + + There is no technical basis for this value; it was determined based on + experiments conducted by Szymon Parapura. + */ + static constexpr double altitude_threshold_ = 1.0; + /** @defgroup cache * Declared mutable for caching */ diff --git a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp index b6f9406a8d8..55a71850e49 100644 --- a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp +++ b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp @@ -332,7 +332,7 @@ auto HdMapUtils::getNearbyLaneletIds( return lanelet_ids; } -auto HdMapUtils::getHeight(const traffic_simulator_msgs::msg::LaneletPose & lanelet_pose) const +auto HdMapUtils::getAltitude(const traffic_simulator_msgs::msg::LaneletPose & lanelet_pose) const -> double { return toMapPose(lanelet_pose).pose.position.z; @@ -593,6 +593,11 @@ auto HdMapUtils::toLaneletPose( return std::nullopt; } auto pose_on_centerline = spline->getPose(s.value()); + + if (!isAltitudeMatching(pose.position.z, pose_on_centerline.position.z)) { + return std::nullopt; + } + auto rpy = math::geometry::convertQuaternionToEulerAngle( math::geometry::getRotation(pose_on_centerline.orientation, pose.orientation)); double offset = std::sqrt(spline->getSquaredDistanceIn2D(pose.position, s.value())); @@ -616,6 +621,12 @@ auto HdMapUtils::toLaneletPose( return lanelet_pose; } +auto HdMapUtils::isAltitudeMatching( + const double current_altitude, const double target_altitude) const -> bool +{ + return std::abs(current_altitude - target_altitude) <= altitude_threshold_; +} + auto HdMapUtils::toLaneletPose( const geometry_msgs::msg::Pose & pose, const lanelet::Ids & lanelet_ids, const double matching_distance) const -> std::optional From c1b4d1f9d55f704435018e070bb60b9a7a0bc99d Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Sun, 8 Dec 2024 17:17:16 +0100 Subject: [PATCH 28/54] [RJD-1369] Improve Collision Solving for Multi-Level Support - Enhanced BehaviorTree to consider altitude when detecting potential obstacles, allowing to ignore objects located at different altitudes. - Modified the detection sensor by introducing Ego plane determination to exclude objects below the Ego plane, preventing unnecessary slowing or stopping caused by incorrect detections. --- .../math/geometry/include/geometry/plane.hpp | 42 +++++++++++++++ .../quaternion/get_angle_difference.hpp | 39 ++++++++++++++ .../geometry/quaternion/get_normal_vector.hpp | 41 +++++++++++++++ common/math/geometry/src/plane.cpp | 48 +++++++++++++++++ .../behavior_tree_plugin/action_node.hpp | 2 + .../behavior_tree_plugin/src/action_node.cpp | 10 +++- .../detection_sensor/detection_sensor.hpp | 42 ++++++++++++++- .../detection_sensor/detection_sensor.cpp | 52 +++++++++++++++++++ 8 files changed, 274 insertions(+), 2 deletions(-) create mode 100644 common/math/geometry/include/geometry/plane.hpp create mode 100644 common/math/geometry/include/geometry/quaternion/get_angle_difference.hpp create mode 100644 common/math/geometry/include/geometry/quaternion/get_normal_vector.hpp create mode 100644 common/math/geometry/src/plane.cpp diff --git a/common/math/geometry/include/geometry/plane.hpp b/common/math/geometry/include/geometry/plane.hpp new file mode 100644 index 00000000000..a718c319bd7 --- /dev/null +++ b/common/math/geometry/include/geometry/plane.hpp @@ -0,0 +1,42 @@ +// 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 GEOMETRY__PLANE_HPP_ +#define GEOMETRY__PLANE_HPP_ + +#include +#include +#include +#include + +namespace math +{ +namespace geometry +{ +struct Plane +{ + geometry_msgs::msg::Vector3 normal_; + double d_; + + Plane(const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Vector3 & normal); + auto calculateOffset(const geometry_msgs::msg::Point & point) -> double; +}; + +auto makePlane(const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Vector3 & normal) + -> std::optional; + +} // namespace geometry +} // namespace math + +#endif // GEOMETRY__PLANE_HPP_ diff --git a/common/math/geometry/include/geometry/quaternion/get_angle_difference.hpp b/common/math/geometry/include/geometry/quaternion/get_angle_difference.hpp new file mode 100644 index 00000000000..298a9e2d481 --- /dev/null +++ b/common/math/geometry/include/geometry/quaternion/get_angle_difference.hpp @@ -0,0 +1,39 @@ +// 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 GEOMETRY__QUATERNION__GET_ANGLE_DIFFERENCE_HPP_ +#define GEOMETRY__QUATERNION__GET_ANGLE_DIFFERENCE_HPP_ + +#include // Załaduj biblioteki Eigen +#include + +namespace math +{ +namespace geometry +{ +template < + typename T, std::enable_if_t>, std::nullptr_t> = nullptr> +auto getAngleDifference(const T & quat1, const T & quat2) -> double +{ + const Eigen::Quaterniond q1(quat1.w, quat1.x, quat1.y, quat1.z); + const Eigen::Quaterniond q2(quat2.w, quat2.x, quat2.y, quat2.z); + + Eigen::AngleAxisd delta(q1.inverse() * q2); + + return std::abs(delta.angle()); // [rad] +} +} // namespace geometry +} // namespace math + +#endif // GEOMETRY__QUATERNION__GET_ANGLE_DIFFERENCE_HPP_ diff --git a/common/math/geometry/include/geometry/quaternion/get_normal_vector.hpp b/common/math/geometry/include/geometry/quaternion/get_normal_vector.hpp new file mode 100644 index 00000000000..b315df00c1a --- /dev/null +++ b/common/math/geometry/include/geometry/quaternion/get_normal_vector.hpp @@ -0,0 +1,41 @@ +// 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 GEOMETRY__VECTOR3__GET_NORMAL_VECTOR_HPP_ +#define GEOMETRY__VECTOR3__GET_NORMAL_VECTOR_HPP_ + +#include +#include +#include + +namespace math +{ +namespace geometry +{ +template < + typename T, std::enable_if_t>, std::nullptr_t> = nullptr> +auto getNormalVector(const T & orientation) -> geometry_msgs::msg::Vector3 +{ + const Eigen::Matrix3d rotation_matrix = getRotationMatrix(orientation); + + return geometry_msgs::build() + .x(rotation_matrix(0, 2)) + .y(rotation_matrix(1, 2)) + .z(rotation_matrix(2, 2)); +} + +} // namespace geometry +} // namespace math + +#endif // GEOMETRY__VECTOR3__GET_NORMAL_VECTOR_HPP_ \ No newline at end of file diff --git a/common/math/geometry/src/plane.cpp b/common/math/geometry/src/plane.cpp new file mode 100644 index 00000000000..ea4805b2bc0 --- /dev/null +++ b/common/math/geometry/src/plane.cpp @@ -0,0 +1,48 @@ +// 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 + +namespace math +{ +namespace geometry +{ + +Plane::Plane(const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Vector3 & normal) +: normal_(normal), d_(-(normal.x * point.x + normal.y * point.y + normal.z * point.z)) +{ +} + +auto Plane::calculateOffset(const geometry_msgs::msg::Point & point) -> double +{ + return normal_.x * point.x + normal_.y * point.y + normal_.z * point.z + d_; +} + +auto makePlane(const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Vector3 & normal) + -> std::optional +{ + if (normal.x == 0.0 && normal.y == 0.0 && normal.z == 0.0) { + return std::nullopt; + } + + if (std::isnan(point.x) || std::isnan(point.y) || std::isnan(point.z)) { + return std::nullopt; + } + + return Plane(point, normal); +} + +} // namespace geometry +} // namespace math diff --git a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp index 4bcba6c41cc..0b2c7350e5d 100644 --- a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp +++ b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp @@ -139,6 +139,8 @@ class ActionNode : public BT::ActionNodeBase -> std::vector; auto getConflictingEntityStatusOnLane(const lanelet::Ids & route_lanelets) const -> std::vector; + auto isEntityAltitudeCompatible( + const traffic_simulator::CanonicalizedEntityStatus & other_entity_status) const -> bool; }; } // namespace entity_behavior diff --git a/simulation/behavior_tree_plugin/src/action_node.cpp b/simulation/behavior_tree_plugin/src/action_node.cpp index cbe86b1c649..82f77d43358 100644 --- a/simulation/behavior_tree_plugin/src/action_node.cpp +++ b/simulation/behavior_tree_plugin/src/action_node.cpp @@ -316,7 +316,7 @@ auto ActionNode::getDistanceToTargetEntityPolygon( double width_extension_left, double length_extension_front, double length_extension_rear) const -> std::optional { - if (status.laneMatchingSucceed()) { + if (status.laneMatchingSucceed() && isEntityAltitudeCompatible(status)) { const auto polygon = math::geometry::transformPoints( status.getMapPose(), math::geometry::getPointsFromBbox( status.getBoundingBox(), width_extension_right, width_extension_left, @@ -326,6 +326,14 @@ auto ActionNode::getDistanceToTargetEntityPolygon( return std::nullopt; } +auto ActionNode::isEntityAltitudeCompatible( + const traffic_simulator::CanonicalizedEntityStatus & other_entity_status) const -> bool +{ + return hdmap_utils->isAltitudeMatching( + hdmap_utils->getAltitude(canonicalized_entity_status->getLaneletPose()), + hdmap_utils->getAltitude(other_entity_status.getLaneletPose())); +} + auto ActionNode::getDistanceToConflictingEntity( const lanelet::Ids & route_lanelets, const math::geometry::CatmullRomSplineInterface & spline) const -> std::optional diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp index f5545a0d9d4..33de5b9b8f1 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp @@ -17,7 +17,10 @@ #include +#include +#include #include +#include #include #include #include @@ -37,7 +40,11 @@ class DetectionSensorBase explicit DetectionSensorBase( const double current_simulation_time, const simulation_api_schema::DetectionSensorConfiguration & configuration) - : previous_simulation_time_(current_simulation_time), configuration_(configuration) + : previous_simulation_time_(current_simulation_time), + configuration_(configuration), + ego_pose_(), + previous_ego_pose_(std::nullopt), + ego_plane_(std::nullopt) { } @@ -48,6 +55,9 @@ class DetectionSensorBase const std::vector &) const -> std::vector::const_iterator; + auto isOnOrAboveEgoPlane( + const geometry_msgs::Pose & npc_pose, const geometry_msgs::Pose & ego_pose) -> bool; + public: virtual ~DetectionSensorBase() = default; @@ -55,6 +65,36 @@ class DetectionSensorBase const double current_simulation_time, const std::vector &, const rclcpp::Time & current_ros_time, const std::vector & lidar_detected_entities) = 0; + +private: + /* + The threshold for detecting significant changes in ego vehicle's orientation (unit: radian). + The value determines the minimum angular difference required to consider the ego orientation + as "changed". + + There is no technical basis for this value, it was determined based on Szymon Parapura + experiments. + */ + constexpr static double rotation_threshold_ = 0.04; + + /* + Maximum downward offset in Z-axis relative to the ego position (unit: meter). + If the NPC is lower than this offset relative to the ego position, + the NPC will be excluded from detection + + There is no technical basis for this value, it was determined based on Szymon Parapura + experiments. + */ + constexpr static double max_downward_z_offset_ = 1.0; + + geometry_msgs::msg::Pose ego_pose_; + std::optional previous_ego_pose_; + std::optional ego_plane_; + + auto isAltitudeDifferenceWithinThreshold(const geometry_msgs::msg::Pose & entity_pose) const + -> bool; + auto needToUpdateEgoPlane() const -> bool; + auto hasEgoOrientationChanged() const -> bool; }; template diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp index 23b38f4b094..187d93eab60 100644 --- a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp @@ -19,6 +19,8 @@ #include #include #include +#include +#include #include #include #include @@ -62,6 +64,55 @@ auto DetectionSensorBase::findEgoEntityStatusToWhichThisSensorIsAttached( } } +auto DetectionSensorBase::isOnOrAboveEgoPlane( + const geometry_msgs::Pose & npc_pose, const geometry_msgs::Pose & ego_pose) -> bool +{ + using math::geometry::getNormalVector; + using math::geometry::makePlane; + + geometry_msgs::msg::Pose entity_pose; + simulation_interface::toMsg(ego_pose, ego_pose_); + simulation_interface::toMsg(npc_pose, entity_pose); + + if (isAltitudeDifferenceWithinThreshold(entity_pose)) { + return true; + } + + if (needToUpdateEgoPlane()) { + ego_plane_ = makePlane(ego_pose_.position, getNormalVector(ego_pose_.orientation)); + if (ego_plane_) { + previous_ego_pose_ = ego_pose_; + } else { + return false; + } + } + + return ego_plane_.value().calculateOffset(entity_pose.position) >= 0.0; +} + +auto DetectionSensorBase::isAltitudeDifferenceWithinThreshold( + const geometry_msgs::msg::Pose & entity_pose) const -> bool +{ + return entity_pose.position.z >= (ego_pose_.position.z - max_downward_z_offset_); +} + +auto DetectionSensorBase::needToUpdateEgoPlane() const -> bool +{ + return !ego_plane_ || hasEgoOrientationChanged(); +} + +auto DetectionSensorBase::hasEgoOrientationChanged() const -> bool +{ + using math::geometry::getAngleDifference; + + if (!previous_ego_pose_) { + return true; + } + + return getAngleDifference(ego_pose_.orientation, previous_ego_pose_.value().orientation) > + rotation_threshold_; +} + template auto make(From &&...) -> To; @@ -322,6 +373,7 @@ auto DetectionSensor::updat auto is_in_range = [&](const auto & status) { return not isEgoEntityStatusToWhichThisSensorIsAttached(status) and distance(status.pose(), ego_entity_status->pose()) <= configuration_.range() and + isOnOrAboveEgoPlane(status.pose(), ego_entity_status->pose()) and (configuration_.detect_all_objects_in_range() or std::find( lidar_detected_entities.begin(), lidar_detected_entities.end(), status.name()) != From 21baa9e093eb4b46c925097736aa8e34755ecaed Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Mon, 9 Dec 2024 10:17:04 +0100 Subject: [PATCH 29/54] Fix missing newline at end of file --- .../geometry/include/geometry/quaternion/get_normal_vector.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/math/geometry/include/geometry/quaternion/get_normal_vector.hpp b/common/math/geometry/include/geometry/quaternion/get_normal_vector.hpp index b315df00c1a..318a239c16d 100644 --- a/common/math/geometry/include/geometry/quaternion/get_normal_vector.hpp +++ b/common/math/geometry/include/geometry/quaternion/get_normal_vector.hpp @@ -38,4 +38,4 @@ auto getNormalVector(const T & orientation) -> geometry_msgs::msg::Vector3 } // namespace geometry } // namespace math -#endif // GEOMETRY__VECTOR3__GET_NORMAL_VECTOR_HPP_ \ No newline at end of file +#endif // GEOMETRY__VECTOR3__GET_NORMAL_VECTOR_HPP_ From d27b8f5ebe2f11a8b167dc7d614b1c60f86fb836 Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Mon, 9 Dec 2024 11:20:02 +0100 Subject: [PATCH 30/54] Removed unrecognized words because spell-check flagged them as invalid --- .../sensor_simulation/detection_sensor/detection_sensor.hpp | 6 ++---- .../include/traffic_simulator/hdmap_utils/hdmap_utils.hpp | 2 +- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp index 33de5b9b8f1..b220571ef7a 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp @@ -72,8 +72,7 @@ class DetectionSensorBase The value determines the minimum angular difference required to consider the ego orientation as "changed". - There is no technical basis for this value, it was determined based on Szymon Parapura - experiments. + There is no technical basis for this value, it was determined based on experiments. */ constexpr static double rotation_threshold_ = 0.04; @@ -82,8 +81,7 @@ class DetectionSensorBase If the NPC is lower than this offset relative to the ego position, the NPC will be excluded from detection - There is no technical basis for this value, it was determined based on Szymon Parapura - experiments. + There is no technical basis for this value, it was determined based on experiments. */ constexpr static double max_downward_z_offset_ = 1.0; diff --git a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp index 618b63b688d..6e5bec89712 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp @@ -394,7 +394,7 @@ class HdMapUtils the center of the rear axle projected onto the ground in the case of vehicles. There is no technical basis for this value; it was determined based on - experiments conducted by Szymon Parapura. + experiments. */ static constexpr double altitude_threshold_ = 1.0; From 729c31f61c7c3846493b9b4f99e526f4c5c56be7 Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Mon, 9 Dec 2024 16:13:52 +0100 Subject: [PATCH 31/54] Fix an issue with unit tests - distanceTest --- .../test/src/hdmap_utils/test_hdmap_utils.cpp | 6 +- .../test/src/helper_functions.hpp | 5 +- .../test/src/utils/test_distance.cpp | 116 +++++++++--------- 3 files changed, 65 insertions(+), 62 deletions(-) diff --git a/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp b/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp index eaa36c849a4..dd0dda7330f 100644 --- a/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp +++ b/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp @@ -2098,9 +2098,11 @@ TEST_F(HdMapUtilsTest_StandardMap, getLongitudinalDistance_differentLanelet) TEST_F(HdMapUtilsTest_FourTrackHighwayMap, getLongitudinalDistance_differentLaneletNoRoute) { const auto pose_to = hdmap_utils.toLaneletPose( - makePose(makePoint(81590.79, 50067.66), makeQuaternionFromYaw(90.0)), lanelet::Id{3002185}); + makePose(makePoint(81590.79, 50067.66, 35.0), makeQuaternionFromYaw(90.0)), + lanelet::Id{3002185}); const auto pose_from = hdmap_utils.toLaneletPose( - makePose(makePoint(81596.20, 50068.04), makeQuaternionFromYaw(90.0)), lanelet::Id{3002166}); + makePose(makePoint(81596.20, 50068.04, 35.0), makeQuaternionFromYaw(90.0)), + lanelet::Id{3002166}); ASSERT_TRUE(pose_from.has_value()); ASSERT_TRUE(pose_to.has_value()); diff --git a/simulation/traffic_simulator/test/src/helper_functions.hpp b/simulation/traffic_simulator/test/src/helper_functions.hpp index a12b5e33328..c10cc1d4931 100644 --- a/simulation/traffic_simulator/test/src/helper_functions.hpp +++ b/simulation/traffic_simulator/test/src/helper_functions.hpp @@ -63,13 +63,14 @@ auto makeQuaternionFromYaw(const double yaw) -> geometry_msgs::msg::Quaternion geometry_msgs::build().x(0.0).y(0.0).z(yaw)); } -auto makePose(const double x, const double y, const double yaw_deg) -> geometry_msgs::msg::Pose +auto makePose(const double x, const double y, const double z, const double yaw_deg) + -> geometry_msgs::msg::Pose { /** * @note +x axis is 0 degrees; +y axis is 90 degrees */ return geometry_msgs::build() - .position(geometry_msgs::build().x(x).y(y).z(0.0)) + .position(geometry_msgs::build().x(x).y(y).z(z)) .orientation(math::geometry::convertEulerAngleToQuaternion( geometry_msgs::build().x(0.0).y(0.0).z( convertDegToRad(yaw_deg)))); diff --git a/simulation/traffic_simulator/test/src/utils/test_distance.cpp b/simulation/traffic_simulator/test/src/utils/test_distance.cpp index ebe1558fb98..d670eeef614 100644 --- a/simulation/traffic_simulator/test/src/utils/test_distance.cpp +++ b/simulation/traffic_simulator/test/src/utils/test_distance.cpp @@ -238,10 +238,10 @@ TEST_F(distanceTest_FourTrackHighwayMap, longitudinalDistance_noAdjacent_noOppos { { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81595.44, 50006.09, 100.0), false, hdmap_utils_ptr); + makePose(81595.44, 50006.09, 35.0, 100.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81584.48, 50084.76, 100.0), false, hdmap_utils_ptr); + makePose(81584.48, 50084.76, 35.0, 100.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto result = traffic_simulator::distance::longitudinalDistance( @@ -260,10 +260,10 @@ TEST_F(distanceTest_StandardMap, longitudinalDistance_noAdjacent_noOpposite_noCh { { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(3800.05, 73715.77, 30.0), false, hdmap_utils_ptr); + makePose(3800.05, 73715.77, 0.5, 30.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(3841.26, 73748.80, 110.0), false, hdmap_utils_ptr); + makePose(3841.26, 73748.80, 0.5, 110.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto result = traffic_simulator::distance::longitudinalDistance( @@ -283,10 +283,10 @@ TEST_F(distanceTest_FourTrackHighwayMap, longitudinalDistance_adjacent_noOpposit { { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81585.79, 50042.62, 100.0), false, hdmap_utils_ptr); + makePose(81585.79, 50042.62, 35.0, 100.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81588.34, 50083.23, 100.0), false, hdmap_utils_ptr); + makePose(81588.34, 50083.23, 35.0, 100.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto result = traffic_simulator::distance::longitudinalDistance( @@ -305,10 +305,10 @@ TEST_F(distanceTest_FourTrackHighwayMap, longitudinalDistance_adjacent_noOpposit { { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81599.02, 50065.76, 280.0), false, hdmap_utils_ptr); + makePose(81599.02, 50065.76, 35.0, 280.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81599.61, 50045.16, 280.0), false, hdmap_utils_ptr); + makePose(81599.61, 50045.16, 35.0, 280.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto result = traffic_simulator::distance::longitudinalDistance( @@ -328,10 +328,10 @@ TEST_F(distanceTest_FourTrackHighwayMap, longitudinalDistance_noAdjacent_noOppos { { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81595.47, 49982.80, 100.0), false, hdmap_utils_ptr); + makePose(81595.47, 49982.80, 36.0, 100.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81599.34, 50022.34, 100.0), false, hdmap_utils_ptr); + makePose(81599.34, 50022.34, 35.0, 100.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); traffic_simulator::RoutingConfiguration lane_changeable_routing_configuration; @@ -343,10 +343,10 @@ TEST_F(distanceTest_FourTrackHighwayMap, longitudinalDistance_noAdjacent_noOppos } { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81612.35, 50015.63, 280.0), false, hdmap_utils_ptr); + makePose(81612.35, 50015.63, 35.0, 280.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81612.95, 49991.30, 280.0), false, hdmap_utils_ptr); + makePose(81612.95, 49991.30, 35.5, 280.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); traffic_simulator::RoutingConfiguration lane_changeable_routing_configuration; @@ -367,10 +367,10 @@ TEST_F(distanceTest_FourTrackHighwayMap, longitudinalDistance_noAdjacent_noOppos { { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81592.96, 49997.94, 100.0), false, hdmap_utils_ptr); + makePose(81592.96, 49997.94, 35.0, 100.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81570.56, 50141.75, 100.0), false, hdmap_utils_ptr); + makePose(81570.56, 50141.75, 35.0, 100.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); traffic_simulator::RoutingConfiguration lane_changeable_routing_configuration; @@ -383,10 +383,10 @@ TEST_F(distanceTest_FourTrackHighwayMap, longitudinalDistance_noAdjacent_noOppos } { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81587.31, 50165.57, 100.0), false, hdmap_utils_ptr); + makePose(81587.31, 50165.57, 35.0, 100.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81610.25, 49988.59, 100.0), false, hdmap_utils_ptr); + makePose(81610.25, 49988.59, 35.5, 100.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); traffic_simulator::RoutingConfiguration lane_changeable_routing_configuration; @@ -406,10 +406,10 @@ TEST_F(distanceTest_IntersectionMap, longitudinalDistance_noAdjacent_noOpposite_ { { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86627.71, 44972.06, 340.0), false, hdmap_utils_ptr); + makePose(86627.71, 44972.06, 3.0, 340.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86647.23, 44882.51, 240.0), false, hdmap_utils_ptr); + makePose(86647.23, 44882.51, 3.0, 240.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); traffic_simulator::RoutingConfiguration lane_changeable_routing_configuration; @@ -421,10 +421,10 @@ TEST_F(distanceTest_IntersectionMap, longitudinalDistance_noAdjacent_noOpposite_ } { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86555.38, 45000.88, 340.0), false, hdmap_utils_ptr); + makePose(86555.38, 45000.88, 3.0, 340.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86647.23, 44882.51, 240.0), false, hdmap_utils_ptr); + makePose(86647.23, 44882.51, 3.0, 240.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); traffic_simulator::RoutingConfiguration lane_changeable_routing_configuration; @@ -436,10 +436,10 @@ TEST_F(distanceTest_IntersectionMap, longitudinalDistance_noAdjacent_noOpposite_ } { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86788.82, 44993.77, 210.0), false, hdmap_utils_ptr); + makePose(86788.82, 44993.77, 3.0, 210.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86553.48, 44990.56, 150.0), false, hdmap_utils_ptr); + makePose(86553.48, 44990.56, 3.0, 150.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); traffic_simulator::RoutingConfiguration lane_changeable_routing_configuration; @@ -451,10 +451,10 @@ TEST_F(distanceTest_IntersectionMap, longitudinalDistance_noAdjacent_noOpposite_ } { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86788.82, 44993.77, 210.0), false, hdmap_utils_ptr); + makePose(86788.82, 44993.77, 3.0, 210.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86579.91, 44979.00, 150.0), false, hdmap_utils_ptr); + makePose(86579.91, 44979.00, 3.0, 150.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); traffic_simulator::RoutingConfiguration lane_changeable_routing_configuration; @@ -475,10 +475,10 @@ TEST_F(distanceTest_IntersectionMap, longitudinalDistance_adjacent_noOpposite_ch { { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86736.13, 44969.63, 210.0), false, hdmap_utils_ptr); + makePose(86736.13, 44969.63, 3.0, 210.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86642.95, 44958.78, 340.0), false, hdmap_utils_ptr); + makePose(86642.95, 44958.78, 3.0, 340.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); traffic_simulator::RoutingConfiguration lane_changeable_routing_configuration; @@ -490,10 +490,10 @@ TEST_F(distanceTest_IntersectionMap, longitudinalDistance_adjacent_noOpposite_ch } { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86732.06, 44976.58, 210.0), false, hdmap_utils_ptr); + makePose(86732.06, 44976.58, 3.0, 210.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86704.59, 44927.32, 340.0), false, hdmap_utils_ptr); + makePose(86704.59, 44927.32, 3.0, 340.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); traffic_simulator::RoutingConfiguration lane_changeable_routing_configuration; @@ -514,9 +514,9 @@ TEST_F(distanceTest_IntersectionMap, longitudinalDistance_adjacent_noOpposite_ch { { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86637.19, 44967.35, 340.0), false, hdmap_utils_ptr); + makePose(86637.19, 44967.35, 3.0, 340.0), false, hdmap_utils_ptr); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86648.82, 44886.19, 240.0), false, hdmap_utils_ptr); + makePose(86648.82, 44886.19, 3.0, 240.0), false, hdmap_utils_ptr); traffic_simulator::RoutingConfiguration lane_changeable_routing_configuration; lane_changeable_routing_configuration.allow_lane_change = true; @@ -528,10 +528,10 @@ TEST_F(distanceTest_IntersectionMap, longitudinalDistance_adjacent_noOpposite_ch } { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86719.94, 44957.20, 210.0), false, hdmap_utils_ptr); + makePose(86719.94, 44957.20, 3.0, 210.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86599.32, 44975.01, 180.0), false, hdmap_utils_ptr); + makePose(86599.32, 44975.01, 3.0, 180.0), false, hdmap_utils_ptr); ASSERT_TRUE(pose_from.has_value()); traffic_simulator::RoutingConfiguration lane_changeable_routing_configuration; @@ -550,8 +550,8 @@ TEST_F(distanceTest_IntersectionMap, longitudinalDistance_adjacent_noOpposite_ch */ TEST(distance, boundingBoxDistance_intersection) { - const auto pose_from = makePose(100.0, 100.0, 0.0); - const auto pose_to = makePose(120.0, 100.0, 90.0); + const auto pose_from = makePose(100.0, 100.0, 0.0, 0.0); + const auto pose_to = makePose(120.0, 100.0, 0.0, 90.0); const auto bounding_box_from = makeCustom2DBoundingBox(30.0, 1.0); const auto bounding_box_to = makeCustom2DBoundingBox(1.0, 30.0); @@ -569,8 +569,8 @@ TEST(distance, boundingBoxDistance_intersection) */ TEST(distance, boundingBoxDistance_disjoint) { - const auto pose_from = makePose(100.0, 100.0, 0.0); - const auto pose_to = makePose(120.0, 100.0, 90.0); + const auto pose_from = makePose(100.0, 100.0, 0.0, 0.0); + const auto pose_to = makePose(120.0, 100.0, 0.0, 90.0); const auto bounding_box_from = makeCustom2DBoundingBox(1.0, 30.0); const auto bounding_box_to = makeCustom2DBoundingBox(30.0, 1.0); @@ -592,56 +592,56 @@ TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_single) constexpr lanelet::Id lanelet_id = 34741L; constexpr double tolerance = 0.1; { - const auto pose = makePose(3818.33, 73726.18, 30.0); + const auto pose = makePose(3818.33, 73726.18, 0.0, 30.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 0.5, tolerance); } { - const auto pose = makePose(3816.89, 73723.09, 30.0); + const auto pose = makePose(3816.89, 73723.09, 0.0, 30.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 2.6, tolerance); } { - const auto pose = makePose(3813.42, 73721.11, 30.0); + const auto pose = makePose(3813.42, 73721.11, 0.0, 30.0); const auto bounding_box = makeCustom2DBoundingBox(3.0, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 2.7, tolerance); } { - const auto pose = makePose(3813.42, 73721.11, 120.0); + const auto pose = makePose(3813.42, 73721.11, 0.0, 120.0); const auto bounding_box = makeCustom2DBoundingBox(3.0, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 1.3, tolerance); } { - const auto pose = makePose(3810.99, 73721.40, 30.0); + const auto pose = makePose(3810.99, 73721.40, 0.0, 30.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 1.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 1.4, tolerance); } { - const auto pose = makePose(3810.99, 73721.40, 30.0); + const auto pose = makePose(3810.99, 73721.40, 0.0, 30.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, -1.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 2.4, tolerance); } { - const auto pose = makePose(3680.81, 73757.27, 30.0); + const auto pose = makePose(3680.81, 73757.27, 0.0, 30.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, 34684L, hdmap_utils_ptr); EXPECT_NEAR(result, 5.1, tolerance); } { - const auto pose = makePose(3692.79, 73753.00, 30.0); + const auto pose = makePose(3692.79, 73753.00, 0.0, 30.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, 34684L, hdmap_utils_ptr); @@ -656,7 +656,7 @@ TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_single) TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_multipleVector) { const auto lanelet_ids = lanelet::Ids{34603L, 34600L, 34621L, 34741L}; - const auto pose = makePose(3836.16, 73757.99, 120.0); + const auto pose = makePose(3836.16, 73757.99, 0.0, 120.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double actual_distance = std::transform_reduce( lanelet_ids.cbegin(), lanelet_ids.cend(), std::numeric_limits::max(), @@ -678,7 +678,7 @@ TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_multipleVector) TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_singleVector) { constexpr lanelet::Id lanelet_id = 34426L; - const auto pose = makePose(3693.34, 73738.37, 300.0); + const auto pose = makePose(3693.34, 73738.37, 0.0, 300.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double actual_distance = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); @@ -693,7 +693,7 @@ TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_singleVector) */ TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_emptyVector) { - const auto pose = makePose(3825.87, 73773.08, 135.0); + const auto pose = makePose(3825.87, 73773.08, 0.0, 135.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); EXPECT_THROW( traffic_simulator::distance::distanceToLeftLaneBound( @@ -709,56 +709,56 @@ TEST_F(distanceTest_IntersectionMap, distanceToRightLaneBound_single) constexpr lanelet::Id lanelet_id = 660L; constexpr double tolerance = 0.1; { - const auto pose = makePose(86651.84, 44941.47, 135.0); + const auto pose = makePose(86651.84, 44941.47, 0.0, 135.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 4.1, tolerance); } { - const auto pose = makePose(86653.05, 44946.74, 135.0); + const auto pose = makePose(86653.05, 44946.74, 0.0, 135.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 0.6, tolerance); } { - const auto pose = makePose(86651.47, 44941.07, 120.0); + const auto pose = makePose(86651.47, 44941.07, 0.0, 120.0); const auto bounding_box = makeCustom2DBoundingBox(3.0, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 4.3, tolerance); } { - const auto pose = makePose(86651.47, 44941.07, 210.0); + const auto pose = makePose(86651.47, 44941.07, 0.0, 210.0); const auto bounding_box = makeCustom2DBoundingBox(3.0, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 3.1, tolerance); } { - const auto pose = makePose(86644.10, 44951.86, 150.0); + const auto pose = makePose(86644.10, 44951.86, 0.0, 150.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 1.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 2.0, tolerance); } { - const auto pose = makePose(86644.10, 44951.86, 150.0); + const auto pose = makePose(86644.10, 44951.86, 0.0, 150.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, -1.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 1.1, tolerance); } { - const auto pose = makePose(86644.11, 44941.21, 0.0); + const auto pose = makePose(86644.11, 44941.21, 0.0, 0.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 11.2, tolerance); } { - const auto pose = makePose(86656.83, 44946.96, 0.0); + const auto pose = makePose(86656.83, 44946.96, 0.0, 0.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); @@ -773,7 +773,7 @@ TEST_F(distanceTest_IntersectionMap, distanceToRightLaneBound_single) TEST_F(distanceTest_IntersectionMap, distanceToRightLaneBound_multipleVector) { const auto lanelet_ids = lanelet::Ids{660L, 663L, 684L, 654L, 686L}; - const auto pose = makePose(86642.05, 44902.61, 60.0); + const auto pose = makePose(86642.05, 44902.61, 0.0, 60.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double actual_distance = std::transform_reduce( lanelet_ids.cbegin(), lanelet_ids.cend(), std::numeric_limits::max(), @@ -795,7 +795,7 @@ TEST_F(distanceTest_IntersectionMap, distanceToRightLaneBound_multipleVector) TEST_F(distanceTest_IntersectionMap, distanceToRightLaneBound_singleVector) { constexpr lanelet::Id lanelet_id = 654L; - const auto pose = makePose(86702.79, 44929.05, 150.0); + const auto pose = makePose(86702.79, 44929.05, 0.0, 150.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double actual_distance = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); @@ -810,7 +810,7 @@ TEST_F(distanceTest_IntersectionMap, distanceToRightLaneBound_singleVector) */ TEST_F(distanceTest_IntersectionMap, distanceToRightLaneBound_emptyVector) { - const auto pose = makePose(3825.87, 73773.08, 135.0); + const auto pose = makePose(3825.87, 73773.08, 0.0, 135.0); const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); EXPECT_THROW( traffic_simulator::distance::distanceToRightLaneBound( From fbd15d4c65da769a31a701bb284b82b9ee87acee Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Mon, 9 Dec 2024 19:03:00 +0100 Subject: [PATCH 32/54] [RJD-1370] Fix 3D Lanelet Matching Issue in cpp_mock_scenario - Updated the makeRandomPose method to correctly support 3D lanelet matching. --- .../hdmap_utils/hdmap_utils.hpp | 4 ++++ .../traffic/traffic_source.hpp | 3 ++- .../src/hdmap_utils/hdmap_utils.cpp | 12 ++++++++++++ .../src/traffic/traffic_source.cpp | 17 +++++++++++++++-- 4 files changed, 33 insertions(+), 3 deletions(-) diff --git a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp index 6e5bec89712..e8797a4f3ea 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp @@ -383,6 +383,10 @@ class HdMapUtils auto isAltitudeMatching(const double current_altitude, const double target_altitude) const -> bool; + auto getLaneletAltitude( + const lanelet::Id & lanelet_id, const geometry_msgs::msg::Pose & pose, + const double matching_distance = 1.0) const -> std::optional; + private: /* Using a fixed `altitude_threshold` value of 1.0 [m] is justified because the diff --git a/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_source.hpp b/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_source.hpp index cb2b70636cd..c9daa49273e 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_source.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_source.hpp @@ -117,7 +117,8 @@ class TrafficSource : public TrafficModuleBase const std::size_t id; private: - auto makeRandomPose(const bool random_orientation = false) -> geometry_msgs::msg::Pose; + auto makeRandomPose(const bool random_orientation, const VehicleOrPedestrianParameter & parameter) + -> geometry_msgs::msg::Pose; auto isPoseValid(const VehicleOrPedestrianParameter &, const geometry_msgs::msg::Pose &) -> std::pair>; diff --git a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp index 55a71850e49..8b0909ecba6 100644 --- a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp +++ b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp @@ -2175,6 +2175,18 @@ auto HdMapUtils::toPolygon(const lanelet::ConstLineString3d & line_string) const return ret; } +auto HdMapUtils::getLaneletAltitude( + const lanelet::Id & lanelet_id, const geometry_msgs::msg::Pose & pose, + const double matching_distance) const -> std::optional +{ + if (const auto spline = getCenterPointsSpline(lanelet_id)) { + if (const auto s = spline->getSValue(pose, matching_distance)) { + return spline->getPoint(s.value()).z; + } + } + return std::nullopt; +} + HdMapUtils::RoutingGraphs::RoutingGraphs(const lanelet::LaneletMapPtr & lanelet_map) { vehicle.rules = lanelet::traffic_rules::TrafficRulesFactory::create( diff --git a/simulation/traffic_simulator/src/traffic/traffic_source.cpp b/simulation/traffic_simulator/src/traffic/traffic_source.cpp index 350920a42d1..68f82fdce61 100644 --- a/simulation/traffic_simulator/src/traffic/traffic_source.cpp +++ b/simulation/traffic_simulator/src/traffic/traffic_source.cpp @@ -72,7 +72,9 @@ auto TrafficSource::Validator::operator()( }); } -auto TrafficSource::makeRandomPose(const bool random_orientation) -> geometry_msgs::msg::Pose +auto TrafficSource::makeRandomPose( + const bool random_orientation, const VehicleOrPedestrianParameter & parameter) + -> geometry_msgs::msg::Pose { const double angle = angle_distribution_(engine_); @@ -83,6 +85,17 @@ auto TrafficSource::makeRandomPose(const bool random_orientation) -> geometry_ms random_pose.position.x += radius * std::cos(angle); random_pose.position.y += radius * std::sin(angle); + if (const auto nearby_lanelets = hdmap_utils_->getNearbyLaneletIds( + random_pose.position, radius, std::holds_alternative(parameter)); + !nearby_lanelets.empty()) { + // Get the altitude of the first nearby lanelet + if ( + const auto altitude = + hdmap_utils_->getLaneletAltitude(nearby_lanelets.front(), random_pose, radius)) { + random_pose.position.z = altitude.value(); + } + } + if (random_orientation) { random_pose.orientation = math::geometry::convertEulerAngleToQuaternion( traffic_simulator::helper::constructRPY(0.0, 0.0, angle_distribution_(engine_))); @@ -106,7 +119,7 @@ void TrafficSource::execute( static constexpr auto max_randomization_attempts = 10000; for (auto tries = 0; tries < max_randomization_attempts; ++tries) { - auto candidate_pose = makeRandomPose(configuration_.use_random_orientation); + auto candidate_pose = makeRandomPose(configuration_.use_random_orientation, parameter); if (auto [valid, lanelet_pose] = isPoseValid(parameter, candidate_pose); valid) { return std::make_pair(candidate_pose, lanelet_pose); } From ab76fb074f6cc1028b8172df8acc6e5a5595b75a Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 10 Dec 2024 13:46:24 +0900 Subject: [PATCH 33/54] 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 d64210b4171344b9b1c8edbcfe162b4761c6464c Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Tue, 10 Dec 2024 12:30:47 +0100 Subject: [PATCH 34/54] Remove comment --- .../include/geometry/quaternion/get_angle_difference.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/math/geometry/include/geometry/quaternion/get_angle_difference.hpp b/common/math/geometry/include/geometry/quaternion/get_angle_difference.hpp index 298a9e2d481..8c8ff46265f 100644 --- a/common/math/geometry/include/geometry/quaternion/get_angle_difference.hpp +++ b/common/math/geometry/include/geometry/quaternion/get_angle_difference.hpp @@ -15,7 +15,7 @@ #ifndef GEOMETRY__QUATERNION__GET_ANGLE_DIFFERENCE_HPP_ #define GEOMETRY__QUATERNION__GET_ANGLE_DIFFERENCE_HPP_ -#include // Załaduj biblioteki Eigen +#include #include namespace math From 8e954f489857b95e8f9c5ab92f73e6a319c5a0bd Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Tue, 10 Dec 2024 15:43:58 +0100 Subject: [PATCH 35/54] Refactor code to improve readability based on SonarQube findings --- common/math/geometry/include/geometry/plane.hpp | 2 +- common/math/geometry/src/plane.cpp | 2 +- .../include/behavior_tree_plugin/action_node.hpp | 2 +- simulation/behavior_tree_plugin/src/action_node.cpp | 4 ++-- .../detection_sensor/detection_sensor.hpp | 13 ++++--------- .../detection_sensor/detection_sensor.cpp | 4 ++-- 6 files changed, 11 insertions(+), 16 deletions(-) diff --git a/common/math/geometry/include/geometry/plane.hpp b/common/math/geometry/include/geometry/plane.hpp index a718c319bd7..af442606a14 100644 --- a/common/math/geometry/include/geometry/plane.hpp +++ b/common/math/geometry/include/geometry/plane.hpp @@ -30,7 +30,7 @@ struct Plane double d_; Plane(const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Vector3 & normal); - auto calculateOffset(const geometry_msgs::msg::Point & point) -> double; + auto calculateOffset(const geometry_msgs::msg::Point & point) const -> double; }; auto makePlane(const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Vector3 & normal) diff --git a/common/math/geometry/src/plane.cpp b/common/math/geometry/src/plane.cpp index ea4805b2bc0..16eb761f2e7 100644 --- a/common/math/geometry/src/plane.cpp +++ b/common/math/geometry/src/plane.cpp @@ -25,7 +25,7 @@ Plane::Plane(const geometry_msgs::msg::Point & point, const geometry_msgs::msg:: { } -auto Plane::calculateOffset(const geometry_msgs::msg::Point & point) -> double +auto Plane::calculateOffset(const geometry_msgs::msg::Point & point) const -> double { return normal_.x * point.x + normal_.y * point.y + normal_.z * point.z + d_; } diff --git a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp index 0b2c7350e5d..2ebc7b9446c 100644 --- a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp +++ b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp @@ -140,7 +140,7 @@ class ActionNode : public BT::ActionNodeBase auto getConflictingEntityStatusOnLane(const lanelet::Ids & route_lanelets) const -> std::vector; auto isEntityAltitudeCompatible( - const traffic_simulator::CanonicalizedEntityStatus & other_entity_status) const -> bool; + const traffic_simulator::CanonicalizedEntityStatus & entity_status) const -> bool; }; } // namespace entity_behavior diff --git a/simulation/behavior_tree_plugin/src/action_node.cpp b/simulation/behavior_tree_plugin/src/action_node.cpp index 82f77d43358..49fd3ff33dc 100644 --- a/simulation/behavior_tree_plugin/src/action_node.cpp +++ b/simulation/behavior_tree_plugin/src/action_node.cpp @@ -327,11 +327,11 @@ auto ActionNode::getDistanceToTargetEntityPolygon( } auto ActionNode::isEntityAltitudeCompatible( - const traffic_simulator::CanonicalizedEntityStatus & other_entity_status) const -> bool + const traffic_simulator::CanonicalizedEntityStatus & entity_status) const -> bool { return hdmap_utils->isAltitudeMatching( hdmap_utils->getAltitude(canonicalized_entity_status->getLaneletPose()), - hdmap_utils->getAltitude(other_entity_status.getLaneletPose())); + hdmap_utils->getAltitude(entity_status.getLaneletPose())); } auto ActionNode::getDistanceToConflictingEntity( diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp index 685ed421bd4..177c972247b 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp @@ -40,11 +40,7 @@ class DetectionSensorBase explicit DetectionSensorBase( const double current_simulation_time, const simulation_api_schema::DetectionSensorConfiguration & configuration) - : previous_simulation_time_(current_simulation_time), - configuration_(configuration), - ego_pose_(), - previous_ego_pose_(std::nullopt), - ego_plane_(std::nullopt) + : previous_simulation_time_(current_simulation_time), configuration_(configuration) { } @@ -86,11 +82,10 @@ class DetectionSensorBase constexpr static double max_downward_z_offset_ = 1.0; geometry_msgs::msg::Pose ego_pose_; - std::optional previous_ego_pose_; - std::optional ego_plane_; + std::optional previous_ego_pose_{std::nullopt}; + std::optional ego_plane_{std::nullopt}; - auto isAltitudeDifferenceWithinThreshold(const geometry_msgs::msg::Pose & entity_pose) const - -> bool; + auto isEntityAltitudeAcceptable(const geometry_msgs::msg::Pose & entity_pose) const -> bool; auto needToUpdateEgoPlane() const -> bool; auto hasEgoOrientationChanged() const -> bool; }; diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp index 85f1411fa04..8feb188553f 100644 --- a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp @@ -74,7 +74,7 @@ auto DetectionSensorBase::isOnOrAboveEgoPlane( simulation_interface::toMsg(ego_pose, ego_pose_); simulation_interface::toMsg(npc_pose, entity_pose); - if (isAltitudeDifferenceWithinThreshold(entity_pose)) { + if (isEntityAltitudeAcceptable(entity_pose)) { return true; } @@ -90,7 +90,7 @@ auto DetectionSensorBase::isOnOrAboveEgoPlane( return ego_plane_.value().calculateOffset(entity_pose.position) >= 0.0; } -auto DetectionSensorBase::isAltitudeDifferenceWithinThreshold( +auto DetectionSensorBase::isEntityAltitudeAcceptable( const geometry_msgs::msg::Pose & entity_pose) const -> bool { return entity_pose.position.z >= (ego_pose_.position.z - max_downward_z_offset_); From c6e983e5b62a2a827ba282bc638c325f230796db Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Tue, 10 Dec 2024 20:08:15 +0100 Subject: [PATCH 36/54] ref(traffic_simulator, simple_sensor_simulator): refactor altitude checks --- .github/workflows/custom_spell.json | 4 +- .../math/geometry/include/geometry/plane.hpp | 23 +++--- .../quaternion/get_angle_difference.hpp | 2 +- common/math/geometry/src/plane.cpp | 25 ++----- .../behavior_tree_plugin/action_node.hpp | 2 +- .../behavior_tree_plugin/src/action_node.cpp | 7 +- .../detection_sensor/detection_sensor.hpp | 32 +------- .../detection_sensor/detection_sensor.cpp | 73 ++++++++++--------- .../simulation_interface/conversions.hpp | 15 ++-- .../behavior/behavior_plugin_base.hpp | 14 ++-- .../data_type/entity_status.hpp | 2 + .../hdmap_utils/hdmap_utils.hpp | 14 ---- .../src/data_type/entity_status.cpp | 5 ++ .../src/hdmap_utils/hdmap_utils.cpp | 15 +++- 14 files changed, 104 insertions(+), 129 deletions(-) diff --git a/.github/workflows/custom_spell.json b/.github/workflows/custom_spell.json index 676f628922b..50ca6f5fe94 100644 --- a/.github/workflows/custom_spell.json +++ b/.github/workflows/custom_spell.json @@ -46,6 +46,8 @@ "Tschirnhaus", "walltime", "xerces", - "xercesc" + "xercesc", + "Szymon", + "Parapura" ] } diff --git a/common/math/geometry/include/geometry/plane.hpp b/common/math/geometry/include/geometry/plane.hpp index a718c319bd7..509e3c6e63f 100644 --- a/common/math/geometry/include/geometry/plane.hpp +++ b/common/math/geometry/include/geometry/plane.hpp @@ -15,7 +15,6 @@ #ifndef GEOMETRY__PLANE_HPP_ #define GEOMETRY__PLANE_HPP_ -#include #include #include #include @@ -24,19 +23,23 @@ namespace math { namespace geometry { + +/// @class Plane +/// @brief Represents a plane in 3D space, defined by a normal vector and a point on the plane. +/// +/// The plane is described using the equation: +/// Ax + By + Cz + D = 0 +/// where: +/// - A, B, C are the components of the normal vector (normal_ attribute). +/// - D is the offset from the origin, calculated using the point and normal vector (d_ attribute). struct Plane { - geometry_msgs::msg::Vector3 normal_; - double d_; - Plane(const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Vector3 & normal); - auto calculateOffset(const geometry_msgs::msg::Point & point) -> double; -}; - -auto makePlane(const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Vector3 & normal) - -> std::optional; + auto offset(const geometry_msgs::msg::Point & point) const -> double; + const geometry_msgs::msg::Vector3 normal_; + const double d_; +}; } // namespace geometry } // namespace math - #endif // GEOMETRY__PLANE_HPP_ diff --git a/common/math/geometry/include/geometry/quaternion/get_angle_difference.hpp b/common/math/geometry/include/geometry/quaternion/get_angle_difference.hpp index 8c8ff46265f..4e9450b2b0a 100644 --- a/common/math/geometry/include/geometry/quaternion/get_angle_difference.hpp +++ b/common/math/geometry/include/geometry/quaternion/get_angle_difference.hpp @@ -29,7 +29,7 @@ auto getAngleDifference(const T & quat1, const T & quat2) -> double const Eigen::Quaterniond q1(quat1.w, quat1.x, quat1.y, quat1.z); const Eigen::Quaterniond q2(quat2.w, quat2.x, quat2.y, quat2.z); - Eigen::AngleAxisd delta(q1.inverse() * q2); + const Eigen::AngleAxisd delta(q1.inverse() * q2); return std::abs(delta.angle()); // [rad] } diff --git a/common/math/geometry/src/plane.cpp b/common/math/geometry/src/plane.cpp index ea4805b2bc0..6439839443c 100644 --- a/common/math/geometry/src/plane.cpp +++ b/common/math/geometry/src/plane.cpp @@ -14,35 +14,26 @@ #include #include +#include +#include namespace math { namespace geometry { - Plane::Plane(const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Vector3 & normal) : normal_(normal), d_(-(normal.x * point.x + normal.y * point.y + normal.z * point.z)) { + if (normal.x == 0.0 && normal.y == 0.0 && normal.z == 0.0) { + THROW_SIMULATION_ERROR("Plane cannot be created using zero normal vector."); + } else if (std::isnan(point.x) || std::isnan(point.y) || std::isnan(point.z)) { + THROW_SIMULATION_ERROR("Plane cannot be created using point with NaN value."); + } } -auto Plane::calculateOffset(const geometry_msgs::msg::Point & point) -> double +auto Plane::offset(const geometry_msgs::msg::Point & point) const -> double { return normal_.x * point.x + normal_.y * point.y + normal_.z * point.z + d_; } - -auto makePlane(const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Vector3 & normal) - -> std::optional -{ - if (normal.x == 0.0 && normal.y == 0.0 && normal.z == 0.0) { - return std::nullopt; - } - - if (std::isnan(point.x) || std::isnan(point.y) || std::isnan(point.z)) { - return std::nullopt; - } - - return Plane(point, normal); -} - } // namespace geometry } // namespace math diff --git a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp index 0b2c7350e5d..5e9d6bc968d 100644 --- a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp +++ b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp @@ -139,7 +139,7 @@ class ActionNode : public BT::ActionNodeBase -> std::vector; auto getConflictingEntityStatusOnLane(const lanelet::Ids & route_lanelets) const -> std::vector; - auto isEntityAltitudeCompatible( + auto isOtherEntityAtConsideredAltitude( const traffic_simulator::CanonicalizedEntityStatus & other_entity_status) const -> bool; }; } // namespace entity_behavior diff --git a/simulation/behavior_tree_plugin/src/action_node.cpp b/simulation/behavior_tree_plugin/src/action_node.cpp index 82f77d43358..4e4d0677f84 100644 --- a/simulation/behavior_tree_plugin/src/action_node.cpp +++ b/simulation/behavior_tree_plugin/src/action_node.cpp @@ -316,7 +316,7 @@ auto ActionNode::getDistanceToTargetEntityPolygon( double width_extension_left, double length_extension_front, double length_extension_rear) const -> std::optional { - if (status.laneMatchingSucceed() && isEntityAltitudeCompatible(status)) { + if (status.laneMatchingSucceed() && isOtherEntityAtConsideredAltitude(status)) { const auto polygon = math::geometry::transformPoints( status.getMapPose(), math::geometry::getPointsFromBbox( status.getBoundingBox(), width_extension_right, width_extension_left, @@ -326,12 +326,11 @@ auto ActionNode::getDistanceToTargetEntityPolygon( return std::nullopt; } -auto ActionNode::isEntityAltitudeCompatible( +auto ActionNode::isOtherEntityAtConsideredAltitude( const traffic_simulator::CanonicalizedEntityStatus & other_entity_status) const -> bool { return hdmap_utils->isAltitudeMatching( - hdmap_utils->getAltitude(canonicalized_entity_status->getLaneletPose()), - hdmap_utils->getAltitude(other_entity_status.getLaneletPose())); + canonicalized_entity_status->getAltitude(), other_entity_status.getAltitude()); } auto ActionNode::getDistanceToConflictingEntity( diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp index 685ed421bd4..9a35ef719fc 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp @@ -42,9 +42,8 @@ class DetectionSensorBase const simulation_api_schema::DetectionSensorConfiguration & configuration) : previous_simulation_time_(current_simulation_time), configuration_(configuration), - ego_pose_(), - previous_ego_pose_(std::nullopt), - ego_plane_(std::nullopt) + ego_plane_opt_(std::nullopt), + previous_ego_pose_opt_(std::nullopt) { } @@ -67,31 +66,8 @@ class DetectionSensorBase const std::vector & lidar_detected_entities) = 0; private: - /* - The threshold for detecting significant changes in ego vehicle's orientation (unit: radian). - The value determines the minimum angular difference required to consider the ego orientation - as "changed". - - There is no technical basis for this value, it was determined based on experiments. - */ - constexpr static double rotation_threshold_ = 0.04; - - /* - Maximum downward offset in Z-axis relative to the ego position (unit: meter). - If the NPC is lower than this offset relative to the ego position, - the NPC will be excluded from detection - - There is no technical basis for this value, it was determined based on experiments. - */ - constexpr static double max_downward_z_offset_ = 1.0; - - geometry_msgs::msg::Pose ego_pose_; - std::optional previous_ego_pose_; - std::optional ego_plane_; - - auto isAltitudeDifferenceWithinThreshold(const geometry_msgs::msg::Pose & entity_pose) const - -> bool; - auto needToUpdateEgoPlane() const -> bool; + std::optional ego_plane_opt_; + std::optional previous_ego_pose_opt_; auto hasEgoOrientationChanged() const -> bool; }; diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp index 85f1411fa04..fd85e6d6b8f 100644 --- a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp @@ -65,52 +65,53 @@ auto DetectionSensorBase::findEgoEntityStatusToWhichThisSensorIsAttached( } auto DetectionSensorBase::isOnOrAboveEgoPlane( - const geometry_msgs::Pose & npc_pose, const geometry_msgs::Pose & ego_pose) -> bool + const geometry_msgs::Pose & entity_pose, const geometry_msgs::Pose & ego_pose) -> bool { - using math::geometry::getNormalVector; - using math::geometry::makePlane; + /* + The threshold for detecting significant changes in ego vehicle's orientation (unit: radian). + The value determines the minimum angular difference required to consider the ego orientation + as "changed". - geometry_msgs::msg::Pose entity_pose; - simulation_interface::toMsg(ego_pose, ego_pose_); - simulation_interface::toMsg(npc_pose, entity_pose); + There is no technical basis for this value, it was determined based on experiments. + */ + constexpr static double rotation_threshold_ = 0.04; + /* + Maximum downward offset in Z-axis relative to the ego position (unit: meter). + If the NPC is lower than this offset relative to the ego position, + the NPC will be excluded from detection - if (isAltitudeDifferenceWithinThreshold(entity_pose)) { - return true; - } + There is no technical basis for this value, it was determined based on experiments. + */ + constexpr static double max_downward_z_offset_ = 1.0; - if (needToUpdateEgoPlane()) { - ego_plane_ = makePlane(ego_pose_.position, getNormalVector(ego_pose_.orientation)); - if (ego_plane_) { - previous_ego_pose_ = ego_pose_; + geometry_msgs::msg::Pose ego_pose_ros, entity_pose_ros; + simulation_interface::toMsg(entity_pose, entity_pose_ros); + simulation_interface::toMsg(ego_pose, ego_pose_ros); + + const auto hasEgoOrientationChanged = [this, &entity_pose_ros]() { + if (previous_ego_pose_opt_) { + return true; } else { - return false; + return math::geometry::getAngleDifference( + entity_pose_ros.orientation, previous_ego_pose_opt_->orientation) > + rotation_threshold_; } - } - - return ego_plane_.value().calculateOffset(entity_pose.position) >= 0.0; -} - -auto DetectionSensorBase::isAltitudeDifferenceWithinThreshold( - const geometry_msgs::msg::Pose & entity_pose) const -> bool -{ - return entity_pose.position.z >= (ego_pose_.position.z - max_downward_z_offset_); -} - -auto DetectionSensorBase::needToUpdateEgoPlane() const -> bool -{ - return !ego_plane_ || hasEgoOrientationChanged(); -} + }; -auto DetectionSensorBase::hasEgoOrientationChanged() const -> bool -{ - using math::geometry::getAngleDifference; + // update ego plane if needed + if (!ego_plane_opt_ || hasEgoOrientationChanged()) { + ego_plane_opt_.emplace( + entity_pose_ros.position, math::geometry::getNormalVector(entity_pose_ros.orientation)); + } + previous_ego_pose_opt_ = entity_pose_ros; - if (!previous_ego_pose_) { + // if other entity is just above ego return true + if (entity_pose_ros.position.z >= (ego_pose_ros.position.z - max_downward_z_offset_)) { return true; + // otherwise check if other entity is above ego plane + } else { + return ego_plane_opt_->offset(entity_pose_ros.position) >= 0.0; } - - return getAngleDifference(ego_pose_.orientation, previous_ego_pose_.value().orientation) > - rotation_threshold_; } template diff --git a/simulation/simulation_interface/include/simulation_interface/conversions.hpp b/simulation/simulation_interface/include/simulation_interface/conversions.hpp index 0bd1f09e53f..6e8ee4b7ec8 100644 --- a/simulation/simulation_interface/include/simulation_interface/conversions.hpp +++ b/simulation/simulation_interface/include/simulation_interface/conversions.hpp @@ -168,9 +168,9 @@ void toMsg(const rosgraph_msgs::Clock & proto, rosgraph_msgs::msg::Clock & time) void toProto(const std_msgs::msg::Header & header, std_msgs::Header & proto); void toMsg(const std_msgs::Header & proto, std_msgs::msg::Header & header); -#define DEFINE_CONVERSION(PACKAGE, TYPENAME) \ - auto toProto(const PACKAGE::msg::TYPENAME &, PACKAGE::TYPENAME &)->void; \ - auto toMsg(const PACKAGE::TYPENAME &, PACKAGE::msg::TYPENAME &)->void +#define DEFINE_CONVERSION(PACKAGE, TYPENAME) \ + auto toProto(const PACKAGE::msg::TYPENAME &, PACKAGE::TYPENAME &) -> void; \ + auto toMsg(const PACKAGE::TYPENAME &, PACKAGE::msg::TYPENAME &) -> void DEFINE_CONVERSION(autoware_control_msgs, Lateral); DEFINE_CONVERSION(autoware_control_msgs, Longitudinal); @@ -190,8 +190,7 @@ auto toMsg( { using namespace simulation_api_schema; - auto convert_color = [](auto color) constexpr - { + auto convert_color = [](auto color) constexpr { switch (color) { case TrafficLight_Color_RED: return TrafficLightBulbMessageType::RED; @@ -206,8 +205,7 @@ auto toMsg( } }; - auto convert_shape = [](auto shape) constexpr - { + auto convert_shape = [](auto shape) constexpr { switch (shape) { case TrafficLight_Shape_CIRCLE: return TrafficLightBulbMessageType::CIRCLE; @@ -235,8 +233,7 @@ auto toMsg( } }; - auto convert_status = [](auto status) constexpr - { + auto convert_status = [](auto status) constexpr { switch (status) { case TrafficLight_Status_SOLID_OFF: return TrafficLightBulbMessageType::SOLID_OFF; diff --git a/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp b/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp index f4162f3e9b0..c4dac740c60 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp @@ -44,13 +44,13 @@ class BehaviorPluginBase virtual auto update(const double current_time, const double step_time) -> void = 0; virtual const std::string & getCurrentAction() const = 0; -#define DEFINE_GETTER_SETTER(NAME, KEY, TYPE) \ - virtual TYPE get##NAME() = 0; \ - virtual void set##NAME(const TYPE & value) = 0; \ - auto get##NAME##Key() const->const std::string & \ - { \ - static const std::string key = KEY; \ - return key; \ +#define DEFINE_GETTER_SETTER(NAME, KEY, TYPE) \ + virtual TYPE get##NAME() = 0; \ + virtual void set##NAME(const TYPE & value) = 0; \ + auto get##NAME##Key() const -> const std::string & \ + { \ + static const std::string key = KEY; \ + return key; \ } // clang-format off diff --git a/simulation/traffic_simulator/include/traffic_simulator/data_type/entity_status.hpp b/simulation/traffic_simulator/include/traffic_simulator/data_type/entity_status.hpp index 68a781808a3..b1d07af341f 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/data_type/entity_status.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/data_type/entity_status.hpp @@ -54,6 +54,8 @@ class CanonicalizedEntityStatus auto getMapPose() const noexcept -> const geometry_msgs::msg::Pose &; auto setMapPose(const geometry_msgs::msg::Pose & pose) -> void; + auto getAltitude() const -> double; + auto getTwist() const noexcept -> const geometry_msgs::msg::Twist &; auto setTwist(const geometry_msgs::msg::Twist & twist) -> void; auto setLinearVelocity(double linear_velocity) -> void; diff --git a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp index c3ea1354b54..9be623a2cab 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp @@ -388,20 +388,6 @@ class HdMapUtils const double matching_distance = 1.0) const -> std::optional; private: - /* - Using a fixed `altitude_threshold` value of 1.0 [m] is justified because the - entity's Z-position is always relative to its base. This eliminates the - need to dynamically adjust the threshold based on the entity's dimensions, - ensuring consistent altitude matching regardless of the entity type. - - The position of the entity is defined relative to its base, typically - the center of the rear axle projected onto the ground in the case of vehicles. - - There is no technical basis for this value; it was determined based on - experiments. - */ - static constexpr double altitude_threshold_ = 1.0; - /** @defgroup cache * Declared mutable for caching */ diff --git a/simulation/traffic_simulator/src/data_type/entity_status.cpp b/simulation/traffic_simulator/src/data_type/entity_status.cpp index b2bfb78432e..758d10b6abf 100644 --- a/simulation/traffic_simulator/src/data_type/entity_status.cpp +++ b/simulation/traffic_simulator/src/data_type/entity_status.cpp @@ -122,6 +122,11 @@ auto CanonicalizedEntityStatus::getMapPose() const noexcept -> const geometry_ms return entity_status_.pose; } +auto CanonicalizedEntityStatus::getAltitude() const -> double +{ + return entity_status_.pose.position.z; +} + auto CanonicalizedEntityStatus::getLaneletPose() const noexcept -> const LaneletPose & { if (canonicalized_lanelet_pose_) { diff --git a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp index c35415806bd..eab04aaf2f2 100644 --- a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp +++ b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp @@ -625,7 +625,20 @@ auto HdMapUtils::toLaneletPose( auto HdMapUtils::isAltitudeMatching( const double current_altitude, const double target_altitude) const -> bool { - return std::abs(current_altitude - target_altitude) <= altitude_threshold_; + /* + Using a fixed `altitude_threshold` value of 1.0 [m] is justified because the + entity's Z-position is always relative to its base. This eliminates the + need to dynamically adjust the threshold based on the entity's dimensions, + ensuring consistent altitude matching regardless of the entity type. + + The position of the entity is defined relative to its base, typically + the center of the rear axle projected onto the ground in the case of vehicles. + + There is no technical basis for this value; it was determined based on + experiments. + */ + static constexpr double altitude_threshold = 1.0; + return std::abs(current_altitude - target_altitude) <= altitude_threshold; } auto HdMapUtils::toLaneletPose( From bb0a6bf74930a7302eda787009cabae7a8efdaec Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Tue, 10 Dec 2024 20:14:34 +0100 Subject: [PATCH 37/54] fix(traffic_simulator): revert clang changes --- .../include/simulation_interface/conversions.hpp | 15 +++++++++------ .../behavior/behavior_plugin_base.hpp | 14 +++++++------- 2 files changed, 16 insertions(+), 13 deletions(-) diff --git a/simulation/simulation_interface/include/simulation_interface/conversions.hpp b/simulation/simulation_interface/include/simulation_interface/conversions.hpp index 6e8ee4b7ec8..0bd1f09e53f 100644 --- a/simulation/simulation_interface/include/simulation_interface/conversions.hpp +++ b/simulation/simulation_interface/include/simulation_interface/conversions.hpp @@ -168,9 +168,9 @@ void toMsg(const rosgraph_msgs::Clock & proto, rosgraph_msgs::msg::Clock & time) void toProto(const std_msgs::msg::Header & header, std_msgs::Header & proto); void toMsg(const std_msgs::Header & proto, std_msgs::msg::Header & header); -#define DEFINE_CONVERSION(PACKAGE, TYPENAME) \ - auto toProto(const PACKAGE::msg::TYPENAME &, PACKAGE::TYPENAME &) -> void; \ - auto toMsg(const PACKAGE::TYPENAME &, PACKAGE::msg::TYPENAME &) -> void +#define DEFINE_CONVERSION(PACKAGE, TYPENAME) \ + auto toProto(const PACKAGE::msg::TYPENAME &, PACKAGE::TYPENAME &)->void; \ + auto toMsg(const PACKAGE::TYPENAME &, PACKAGE::msg::TYPENAME &)->void DEFINE_CONVERSION(autoware_control_msgs, Lateral); DEFINE_CONVERSION(autoware_control_msgs, Longitudinal); @@ -190,7 +190,8 @@ auto toMsg( { using namespace simulation_api_schema; - auto convert_color = [](auto color) constexpr { + auto convert_color = [](auto color) constexpr + { switch (color) { case TrafficLight_Color_RED: return TrafficLightBulbMessageType::RED; @@ -205,7 +206,8 @@ auto toMsg( } }; - auto convert_shape = [](auto shape) constexpr { + auto convert_shape = [](auto shape) constexpr + { switch (shape) { case TrafficLight_Shape_CIRCLE: return TrafficLightBulbMessageType::CIRCLE; @@ -233,7 +235,8 @@ auto toMsg( } }; - auto convert_status = [](auto status) constexpr { + auto convert_status = [](auto status) constexpr + { switch (status) { case TrafficLight_Status_SOLID_OFF: return TrafficLightBulbMessageType::SOLID_OFF; diff --git a/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp b/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp index c4dac740c60..f4162f3e9b0 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp @@ -44,13 +44,13 @@ class BehaviorPluginBase virtual auto update(const double current_time, const double step_time) -> void = 0; virtual const std::string & getCurrentAction() const = 0; -#define DEFINE_GETTER_SETTER(NAME, KEY, TYPE) \ - virtual TYPE get##NAME() = 0; \ - virtual void set##NAME(const TYPE & value) = 0; \ - auto get##NAME##Key() const -> const std::string & \ - { \ - static const std::string key = KEY; \ - return key; \ +#define DEFINE_GETTER_SETTER(NAME, KEY, TYPE) \ + virtual TYPE get##NAME() = 0; \ + virtual void set##NAME(const TYPE & value) = 0; \ + auto get##NAME##Key() const->const std::string & \ + { \ + static const std::string key = KEY; \ + return key; \ } // clang-format off From 8cf2c39ad0187868be85e4aa488c0c1eb99c15d2 Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Tue, 10 Dec 2024 20:35:37 +0100 Subject: [PATCH 38/54] fix(simple_sensor_simulator): fix after detection_sensor refactor --- .../detection_sensor/detection_sensor.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp index fd85e6d6b8f..c25fafb8719 100644 --- a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp @@ -88,13 +88,12 @@ auto DetectionSensorBase::isOnOrAboveEgoPlane( simulation_interface::toMsg(entity_pose, entity_pose_ros); simulation_interface::toMsg(ego_pose, ego_pose_ros); - const auto hasEgoOrientationChanged = [this, &entity_pose_ros]() { + const auto hasEgoOrientationChanged = [this, &ego_pose_ros]() { if (previous_ego_pose_opt_) { return true; } else { return math::geometry::getAngleDifference( - entity_pose_ros.orientation, previous_ego_pose_opt_->orientation) > - rotation_threshold_; + ego_pose_ros.orientation, previous_ego_pose_opt_->orientation) > rotation_threshold_; } }; @@ -103,7 +102,7 @@ auto DetectionSensorBase::isOnOrAboveEgoPlane( ego_plane_opt_.emplace( entity_pose_ros.position, math::geometry::getNormalVector(entity_pose_ros.orientation)); } - previous_ego_pose_opt_ = entity_pose_ros; + previous_ego_pose_opt_ = ego_pose_ros; // if other entity is just above ego return true if (entity_pose_ros.position.z >= (ego_pose_ros.position.z - max_downward_z_offset_)) { From 80c5c89aecbe623d989c3c846fc1c612ca7050bb Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Tue, 10 Dec 2024 20:48:27 +0100 Subject: [PATCH 39/54] fix(simple_senor_simulator): fix after Szymon discussion --- .../detection_sensor/detection_sensor.hpp | 4 +-- .../detection_sensor/detection_sensor.cpp | 34 ++++++++----------- 2 files changed, 17 insertions(+), 21 deletions(-) diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp index 9a35ef719fc..237468b0fd8 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp @@ -43,7 +43,7 @@ class DetectionSensorBase : previous_simulation_time_(current_simulation_time), configuration_(configuration), ego_plane_opt_(std::nullopt), - previous_ego_pose_opt_(std::nullopt) + ego_plane_pose_opt_(std::nullopt) { } @@ -67,7 +67,7 @@ class DetectionSensorBase private: std::optional ego_plane_opt_; - std::optional previous_ego_pose_opt_; + std::optional ego_plane_pose_opt_; auto hasEgoOrientationChanged() const -> bool; }; diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp index c25fafb8719..13dad82fb9e 100644 --- a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp @@ -84,31 +84,27 @@ auto DetectionSensorBase::isOnOrAboveEgoPlane( */ constexpr static double max_downward_z_offset_ = 1.0; - geometry_msgs::msg::Pose ego_pose_ros, entity_pose_ros; - simulation_interface::toMsg(entity_pose, entity_pose_ros); - simulation_interface::toMsg(ego_pose, ego_pose_ros); - - const auto hasEgoOrientationChanged = [this, &ego_pose_ros]() { - if (previous_ego_pose_opt_) { - return true; - } else { - return math::geometry::getAngleDifference( - ego_pose_ros.orientation, previous_ego_pose_opt_->orientation) > rotation_threshold_; - } + const auto hasEgoOrientationChanged = [this](const geometry_msgs::msg::Pose & ego_pose_ros) { + return math::geometry::getAngleDifference( + ego_pose_ros.orientation, ego_plane_pose_opt_->orientation) > rotation_threshold_; }; - // update ego plane if needed - if (!ego_plane_opt_ || hasEgoOrientationChanged()) { - ego_plane_opt_.emplace( - entity_pose_ros.position, math::geometry::getNormalVector(entity_pose_ros.orientation)); - } - previous_ego_pose_opt_ = ego_pose_ros; - // if other entity is just above ego return true - if (entity_pose_ros.position.z >= (ego_pose_ros.position.z - max_downward_z_offset_)) { + if (entity_pose.position().z() >= (ego_pose.position().z() - max_downward_z_offset_)) { return true; // otherwise check if other entity is above ego plane } else { + // update ego plane if needed + geometry_msgs::msg::Pose ego_pose_ros; + simulation_interface::toMsg(ego_pose, ego_pose_ros); + if (!ego_plane_opt_ || ego_plane_pose_opt_ || hasEgoOrientationChanged(ego_pose_ros)) { + ego_plane_opt_.emplace( + ego_pose_ros.position, math::geometry::getNormalVector(ego_pose_ros.orientation)); + ego_plane_pose_opt_ = ego_pose_ros; + } + + geometry_msgs::msg::Pose entity_pose_ros; + simulation_interface::toMsg(entity_pose, entity_pose_ros); return ego_plane_opt_->offset(entity_pose_ros.position) >= 0.0; } } From 547cb0adbbfe337355e18e206e746860d111d47e Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Tue, 10 Dec 2024 21:22:38 +0100 Subject: [PATCH 40/54] Remove unused function and update comment --- .../sensor_simulation/detection_sensor/detection_sensor.hpp | 1 - .../src/sensor_simulation/detection_sensor/detection_sensor.cpp | 2 +- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp index 237468b0fd8..67fb5bd3025 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp @@ -68,7 +68,6 @@ class DetectionSensorBase private: std::optional ego_plane_opt_; std::optional ego_plane_pose_opt_; - auto hasEgoOrientationChanged() const -> bool; }; template diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp index 13dad82fb9e..c5f180d70a2 100644 --- a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp @@ -89,7 +89,7 @@ auto DetectionSensorBase::isOnOrAboveEgoPlane( ego_pose_ros.orientation, ego_plane_pose_opt_->orientation) > rotation_threshold_; }; - // if other entity is just above ego return true + // if other entity is at the same altitude as Ego or within max_downward_z_offset_ below Ego if (entity_pose.position().z() >= (ego_pose.position().z() - max_downward_z_offset_)) { return true; // otherwise check if other entity is above ego plane From 682acd3e04f8faa9c5bbe8bd3fe4be44280e1b02 Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Tue, 10 Dec 2024 23:57:59 +0100 Subject: [PATCH 41/54] fix(simple_sensor_simulator): Fix if condition by adding negation to ensure proper logic --- .../detection_sensor/detection_sensor.hpp | 9 +++------ .../detection_sensor/detection_sensor.cpp | 2 +- 2 files changed, 4 insertions(+), 7 deletions(-) diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp index 67fb5bd3025..0aff66be710 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp @@ -40,10 +40,7 @@ class DetectionSensorBase explicit DetectionSensorBase( const double current_simulation_time, const simulation_api_schema::DetectionSensorConfiguration & configuration) - : previous_simulation_time_(current_simulation_time), - configuration_(configuration), - ego_plane_opt_(std::nullopt), - ego_plane_pose_opt_(std::nullopt) + : previous_simulation_time_(current_simulation_time), configuration_(configuration) { } @@ -66,8 +63,8 @@ class DetectionSensorBase const std::vector & lidar_detected_entities) = 0; private: - std::optional ego_plane_opt_; - std::optional ego_plane_pose_opt_; + std::optional ego_plane_opt_{std::nullopt}; + std::optional ego_plane_pose_opt_{std::nullopt}; }; template diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp index c5f180d70a2..cf5925688ff 100644 --- a/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/detection_sensor/detection_sensor.cpp @@ -97,7 +97,7 @@ auto DetectionSensorBase::isOnOrAboveEgoPlane( // update ego plane if needed geometry_msgs::msg::Pose ego_pose_ros; simulation_interface::toMsg(ego_pose, ego_pose_ros); - if (!ego_plane_opt_ || ego_plane_pose_opt_ || hasEgoOrientationChanged(ego_pose_ros)) { + if (!ego_plane_opt_ || !ego_plane_pose_opt_ || hasEgoOrientationChanged(ego_pose_ros)) { ego_plane_opt_.emplace( ego_pose_ros.position, math::geometry::getNormalVector(ego_pose_ros.orientation)); ego_plane_pose_opt_ = ego_pose_ros; From b2a1b1e715950c69594b9d8cae40944a6c27ab8b Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 12 Dec 2024 12:00:03 +0900 Subject: [PATCH 42/54] 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 82b72ce35fc57a451b8c0cdb0f57d03f96f6ce2f Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 12 Dec 2024 15:42:03 +0900 Subject: [PATCH 43/54] Add new enumeration `Compatibility` Signed-off-by: yamacir-kit --- .../compatibility.hpp | 30 +++++++++++++++ .../src/compatibility.cpp | 38 +++++++++++++++++++ .../launch/scenario_test_runner.launch.py | 2 +- 3 files changed, 69 insertions(+), 1 deletion(-) create mode 100644 openscenario/openscenario_interpreter/include/openscenario_interpreter/compatibility.hpp create mode 100644 openscenario/openscenario_interpreter/src/compatibility.cpp diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/compatibility.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/compatibility.hpp new file mode 100644 index 00000000000..683ba6f2377 --- /dev/null +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/compatibility.hpp @@ -0,0 +1,30 @@ +// 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__COMPATIBILITY_HPP_ +#define OPENSCENARIO_INTERPRETER__COMPATIBILITY_HPP_ + +#include + +namespace openscenario_interpreter +{ +enum class Compatibility { + legacy, + standard, +}; + +auto operator>>(std::istream &, Compatibility &) -> std::istream &; +} // namespace openscenario_interpreter + +#endif // OPENSCENARIO_INTERPRETER__COMPATIBILITY_HPP_ diff --git a/openscenario/openscenario_interpreter/src/compatibility.cpp b/openscenario/openscenario_interpreter/src/compatibility.cpp new file mode 100644 index 00000000000..617a5bcc08b --- /dev/null +++ b/openscenario/openscenario_interpreter/src/compatibility.cpp @@ -0,0 +1,38 @@ +// 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 + +namespace openscenario_interpreter +{ +auto operator>>(std::istream & input, Compatibility & compatiblity) -> std::istream & +{ + if (auto token = std::string(); input >> token) { + if (token == "legacy") { + compatiblity = Compatibility::legacy; + return input; + } else if (token == "standard") { + compatiblity = Compatibility::standard; + return input; + } else { + throw Error( + "Unknown compatiblity ", std::quoted(token), + " was specified. It must be \"legacy\" or \"standard\"."); + } + } else { + compatiblity = Compatibility::legacy; + return input; + } +} +} // namespace openscenario_interpreter diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index 98897b9badf..ba38750a462 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -173,8 +173,8 @@ def collect_prefixed_parameters(): DeclareLaunchArgument("global_timeout", default_value=global_timeout ), DeclareLaunchArgument("launch_autoware", default_value=launch_autoware ), DeclareLaunchArgument("launch_rviz", default_value=launch_rviz ), - DeclareLaunchArgument("publish_empty_context", default_value=publish_empty_context ), DeclareLaunchArgument("output_directory", default_value=output_directory ), + DeclareLaunchArgument("publish_empty_context", default_value=publish_empty_context ), DeclareLaunchArgument("rviz_config", default_value=rviz_config ), DeclareLaunchArgument("scenario", default_value=scenario ), DeclareLaunchArgument("sensor_model", default_value=sensor_model ), From 078581360b692e4ddc72d80b50d159ec26130707 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 12 Dec 2024 16:19:24 +0900 Subject: [PATCH 44/54] Add new parameter `speed_condition` to switch compatibility Signed-off-by: yamacir-kit --- .../scenario_simulator_exception/concatenate.hpp | 6 +----- .../openscenario_interpreter/CMakeLists.txt | 3 ++- .../syntax/speed_condition.hpp | 6 +++++- .../src/openscenario_interpreter.cpp | 5 +++++ .../src/syntax/speed_condition.cpp | 13 ++++++++++--- .../launch/scenario_test_runner.launch.py | 4 ++++ 6 files changed, 27 insertions(+), 10 deletions(-) diff --git a/common/scenario_simulator_exception/include/scenario_simulator_exception/concatenate.hpp b/common/scenario_simulator_exception/include/scenario_simulator_exception/concatenate.hpp index 0e967d66821..efb9139b7e2 100644 --- a/common/scenario_simulator_exception/include/scenario_simulator_exception/concatenate.hpp +++ b/common/scenario_simulator_exception/include/scenario_simulator_exception/concatenate.hpp @@ -25,12 +25,8 @@ namespace common inline namespace scenario_simulator_exception { inline auto concatenate = [](auto &&... xs) { - auto write = [](auto && os, auto && x) { - os.get() << std::forward(x); - return std::forward(os); - }; std::stringstream result; - fold_left(write, std::ref(result), std::forward(xs)...); + (result << ... << std::forward(xs)); return result.str(); }; } // namespace scenario_simulator_exception diff --git a/openscenario/openscenario_interpreter/CMakeLists.txt b/openscenario/openscenario_interpreter/CMakeLists.txt index 72ac634e062..a1d95ea6350 100644 --- a/openscenario/openscenario_interpreter/CMakeLists.txt +++ b/openscenario/openscenario_interpreter/CMakeLists.txt @@ -59,8 +59,9 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ${${PROJECT_NAME}_POSIX_SOURCES} ${${PROJECT_NAME}_SYNTAX_SOURCES} ${${PROJECT_NAME}_UTILITY_SOURCES} - src/object.cpp + src/compatibility.cpp src/evaluate.cpp + src/object.cpp src/openscenario_interpreter.cpp src/record.cpp src/scope.cpp) 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 9c2bf1ffb92..f64c7499051 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/speed_condition.hpp @@ -15,6 +15,7 @@ #ifndef OPENSCENARIO_INTERPRETER__SYNTAX__SPEED_CONDITION_HPP_ #define OPENSCENARIO_INTERPRETER__SYNTAX__SPEED_CONDITION_HPP_ +#include #include #include #include @@ -63,6 +64,8 @@ struct SpeedCondition : private Scope, private SimulatorCore::ConditionEvaluatio std::vector> results; // for description + static inline auto compatibility = Compatibility::legacy; + explicit SpeedCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &); auto description() const -> String; @@ -70,7 +73,8 @@ struct SpeedCondition : private Scope, private SimulatorCore::ConditionEvaluatio static auto evaluate(const Entities *, const Entity &) -> Eigen::Vector3d; static auto evaluate( - const Entities *, const Entity &, const std::optional &) -> double; + const Entities *, const Entity &, const std::optional &, + const Compatibility = Compatibility::legacy) -> double; auto evaluate() -> Object; }; diff --git a/openscenario/openscenario_interpreter/src/openscenario_interpreter.cpp b/openscenario/openscenario_interpreter/src/openscenario_interpreter.cpp index d2f7c910cc0..824c83280f3 100644 --- a/openscenario/openscenario_interpreter/src/openscenario_interpreter.cpp +++ b/openscenario/openscenario_interpreter/src/openscenario_interpreter.cpp @@ -22,6 +22,7 @@ #include #include #include +#include #include #include #include @@ -49,6 +50,10 @@ Interpreter::Interpreter(const rclcpp::NodeOptions & options) DECLARE_PARAMETER(output_directory); DECLARE_PARAMETER(publish_empty_context); DECLARE_PARAMETER(record); + + declare_parameter("speed_condition", "legacy"); + SpeedCondition::compatibility = + boost::lexical_cast(get_parameter("speed_condition").as_string()); } Interpreter::~Interpreter() {} diff --git a/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp index cc8d64b0c41..5e2f8e34038 100644 --- a/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/speed_condition.cpp @@ -58,7 +58,8 @@ auto SpeedCondition::evaluate(const Entities * entities, const Entity & triggeri auto SpeedCondition::evaluate( const Entities * entities, const Entity & triggering_entity, - const std::optional & direction) -> double + const std::optional & direction, const Compatibility compatibility) + -> double { if (const Eigen::Vector3d v = evaluate(entities, triggering_entity); direction) { switch (*direction) { @@ -71,7 +72,13 @@ auto SpeedCondition::evaluate( return v.z(); } } else { - return v.norm(); + switch (compatibility) { + default: + case Compatibility::legacy: + return v.x(); + case Compatibility::standard: + return v.norm(); + } } } @@ -81,7 +88,7 @@ auto SpeedCondition::evaluate() -> Object return asBoolean(triggering_entities.apply([&](const auto & triggering_entity) { results.push_back(triggering_entity.apply([&](const auto & triggering_entity) { - return evaluate(global().entities, triggering_entity, direction); + return evaluate(global().entities, triggering_entity, direction, compatibility); })); return not results.back().size() or std::invoke(rule, results.back(), value).min(); })); diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index ba38750a462..fa1492c172c 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -87,6 +87,7 @@ def launch_setup(context, *args, **kwargs): scenario = LaunchConfiguration("scenario", default=Path("/dev/null")) sensor_model = LaunchConfiguration("sensor_model", default="") sigterm_timeout = LaunchConfiguration("sigterm_timeout", default=8) + speed_condition = LaunchConfiguration("speed_condition", default="legacy") use_sim_time = LaunchConfiguration("use_sim_time", default=False) vehicle_model = LaunchConfiguration("vehicle_model", default="") # fmt: on @@ -111,6 +112,7 @@ def launch_setup(context, *args, **kwargs): print(f"scenario := {scenario.perform(context)}") print(f"sensor_model := {sensor_model.perform(context)}") print(f"sigterm_timeout := {sigterm_timeout.perform(context)}") + print(f"speed_condition := {speed_condition.perform(context)}") print(f"use_sim_time := {use_sim_time.perform(context)}") print(f"vehicle_model := {vehicle_model.perform(context)}") @@ -135,6 +137,7 @@ def make_parameters(): {"rviz_config": rviz_config}, {"sensor_model": sensor_model}, {"sigterm_timeout": sigterm_timeout}, + {"speed_condition": speed_condition}, {"use_sim_time": use_sim_time}, {"vehicle_model": vehicle_model}, ] @@ -179,6 +182,7 @@ def collect_prefixed_parameters(): DeclareLaunchArgument("scenario", default_value=scenario ), DeclareLaunchArgument("sensor_model", default_value=sensor_model ), DeclareLaunchArgument("sigterm_timeout", default_value=sigterm_timeout ), + DeclareLaunchArgument("speed_condition", default_value=speed_condition ), DeclareLaunchArgument("use_sim_time", default_value=use_sim_time ), DeclareLaunchArgument("vehicle_model", default_value=vehicle_model ), # fmt: on From 7c4e369d2b1af0e009332ef80237eb09fcf5c01b Mon Sep 17 00:00:00 2001 From: Release Bot Date: Fri, 13 Dec 2024 01:03:45 +0000 Subject: [PATCH 45/54] Bump version of scenario_simulator_v2 from version 7.0.2 to version 7.0.3 --- common/math/arithmetic/CHANGELOG.rst | 8 ++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 8 ++++++++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 8 ++++++++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 8 ++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 8 ++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 10 ++++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 8 ++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 8 ++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 8 ++++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 8 ++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 8 ++++++++ .../openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 8 ++++++++ .../openscenario_interpreter_example/package.xml | 2 +- .../openscenario_interpreter_msgs/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_preprocessor/package.xml | 2 +- .../openscenario_preprocessor_msgs/CHANGELOG.rst | 8 ++++++++ .../openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_validator/package.xml | 2 +- rviz_plugins/openscenario_visualization/CHANGELOG.rst | 8 ++++++++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../real_time_factor_control_rviz_plugin/CHANGELOG.rst | 8 ++++++++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 8 ++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 8 ++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 8 ++++++++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 8 ++++++++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 8 ++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 10 ++++++++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 8 ++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 8 ++++++++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 8 ++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 265 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index b664724b675..b170351db24 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 908b76bdea3..18994179744 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 7.0.2 + 7.0.3 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 398d518f7aa..be0bafab44c 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge pull request `#1470 `_ from tier4/fix/snor-cloud-issue-8-1 diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 5116ae32538..b46f86bb4e6 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 7.0.2 + 7.0.3 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index cf3bc3adf29..a6808384409 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index a005e5748d6..7daa737d657 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 7.0.2 + 7.0.3 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 4a6b3ee0902..5356eb816b0 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 25a635b3db9..c364b08669c 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 7.0.2 + 7.0.3 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 8fe30da0cf0..13ea3091a5c 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 59d9d6502a2..0f936dcaaad 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 7.0.2 + 7.0.3 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index c9ec6fde662..522e1395c67 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,16 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge pull request `#1465 `_ from tier4/fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* fix(concealer): increase max time to request enable autoware control +* Contributors: Kotaro Yoshimoto, satoshi-ota + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/external/concealer/package.xml b/external/concealer/package.xml index a5971def2e4..6807ea82e2a 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 7.0.2 + 7.0.3 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 6661d8bf53c..db9fffa20db 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,14 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 8acfa0e4a14..ac7bbc4d659 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 7.0.2 + 7.0.3 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index db775da252e..9c17f9e8a8b 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 540a6e44ea6..0696ea4827d 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 7.0.2 + 7.0.3 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 9114c7740ce..112a45e7580 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,14 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 0303b2c1d0e..484d8714faa 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 7.0.2 + 7.0.3 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index f493b68bfa7..c66a4cc76cf 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 175546f8e77..92f9ba96f88 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 7.0.2 + 7.0.3 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 4d0dcabb2da..3b56d58375c 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 31f6f183bb3..4c9ed5482c3 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 7.0.2 + 7.0.3 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 813f25e053e..36d4f266144 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,14 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index c7d497d8741..e9fbe1d3598 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 7.0.2 + 7.0.3 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index a600ece6a67..3038b9e4678 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 68ff65fc757..4a31ce56fd8 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 7.0.2 + 7.0.3 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 47881a2a88a..f45a5099e19 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 057014f0ee9..56a95035ba2 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 7.0.2 + 7.0.3 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index a1014e65fde..674191360dc 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 834978f29f0..e91d6109b6e 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 7.0.2 + 7.0.3 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 1f31a52ab4f..4d4702d540a 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index d94c408de3e..d044251414e 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 7.0.2 + 7.0.3 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index b7d93c751f1..06c7e90f7dc 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,14 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index b4f51b923e4..b8c23e528f9 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 7.0.2 + 7.0.3 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index c58b60badaa..68c811fe173 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,14 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index a5dda80e4f9..19840b64144 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 7.0.2 + 7.0.3 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 608a87963bf..f53adfee34f 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge pull request `#1470 `_ from tier4/fix/snor-cloud-issue-8-1 diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 2c596393415..a02db4e9fbd 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 7.0.2 + 7.0.3 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 7bc21f4ad87..fabf001a247 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 8f0243c3744..bce21f3ee2e 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 7.0.2 + 7.0.3 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 84fdea0f5e7..bace7285cff 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 35edc1a1a53..54211af4af7 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 7.0.2 + 7.0.3 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 06d8350c0db..c03dd28c38d 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 9be02b547d4..640aea992d0 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 7.0.2 + 7.0.3 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 57a85dbd380..a2df026aa25 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 9fc2c66d90f..937e3a5441e 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 7.0.2 + 7.0.3 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index d30b0cc1d6f..6727d05b83f 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index bb558e2d07a..1e1d5e3cb84 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 7.0.2 + 7.0.3 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 695f680fc6e..26d57436298 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 21bee384cc4..046efa14c6a 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 7.0.2 + 7.0.3 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 525db7453f5..a3e40444e82 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,16 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge pull request `#1465 `_ from tier4/fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* fix(api): request enable autoware control +* Contributors: Kotaro Yoshimoto, satoshi-ota + 7.0.2 (2024-12-12) ------------------ * Merge pull request `#1470 `_ from tier4/fix/snor-cloud-issue-8-1 diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 19e650a4e2d..d3ceb5ed4f8 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 7.0.2 + 7.0.3 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 63e1f6fcc89..11b944a5910 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index d2c17555369..a872b522734 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 7.0.2 + 7.0.3 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 4340d7352b4..bb5ba5043d1 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 8f1a0332630..0d8796c11b3 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 7.0.2 + 7.0.3 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 39c8efa3a9e..150fe57fb3b 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,14 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.3 (2024-12-13) +------------------ +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Merge branch 'master' into fix/request-enable-autoware-control +* Contributors: Kotaro Yoshimoto + 7.0.2 (2024-12-12) ------------------ * Merge branch 'master' into fix/snor-cloud-issue-8-1 diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index f95ecbcf47a..419a1b7fc01 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 7.0.2 + 7.0.3 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 3255cef0b23139e44e7ceeb19da7bd8b96ee8038 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Fri, 13 Dec 2024 03:27:58 +0000 Subject: [PATCH 46/54] Bump version of scenario_simulator_v2 from version 7.0.3 to version 7.0.4 --- common/math/arithmetic/CHANGELOG.rst | 6 ++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 6 ++++++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 9 +++++++++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 6 ++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 6 ++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 6 ++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 6 ++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 6 ++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 6 ++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 6 ++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 6 ++++++ .../openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 10 ++++++++++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 6 ++++++ .../openscenario_interpreter_example/package.xml | 2 +- .../openscenario_interpreter_msgs/CHANGELOG.rst | 6 ++++++ openscenario/openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 6 ++++++ openscenario/openscenario_preprocessor/package.xml | 2 +- .../openscenario_preprocessor_msgs/CHANGELOG.rst | 6 ++++++ .../openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 6 ++++++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 6 ++++++ openscenario/openscenario_validator/package.xml | 2 +- rviz_plugins/openscenario_visualization/CHANGELOG.rst | 6 ++++++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../real_time_factor_control_rviz_plugin/CHANGELOG.rst | 6 ++++++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 6 ++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 6 ++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 6 ++++++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 6 ++++++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 6 ++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 6 ++++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 6 ++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 6 ++++++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 10 ++++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 214 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index b170351db24..4bb19449115 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 18994179744..15abfa02a91 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 7.0.3 + 7.0.4 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index be0bafab44c..7978b669400 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index b46f86bb4e6..49467cbde14 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 7.0.3 + 7.0.4 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index a6808384409..fb9d82f2305 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge pull request `#1486 `_ from tier4/fix/speed-condition/backward-compatibility + Fix/speed condition/backward compatibility +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Add new parameter `speed_condition` to switch compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 7daa737d657..d82aec6de9a 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 7.0.3 + 7.0.4 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 5356eb816b0..b460aa61a8e 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index c364b08669c..0453c2ae9b0 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 7.0.3 + 7.0.4 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 13ea3091a5c..d83fa605d55 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 0f936dcaaad..30e322eb56e 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 7.0.3 + 7.0.4 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 522e1395c67..d1cd7fcce35 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge pull request `#1465 `_ from tier4/fix/request-enable-autoware-control diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 6807ea82e2a..703a5b23184 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 7.0.3 + 7.0.4 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index db9fffa20db..1f1f5bc5223 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,12 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index ac7bbc4d659..f68ffcd128d 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 7.0.3 + 7.0.4 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 9c17f9e8a8b..852f27c951a 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 0696ea4827d..c111cd34b59 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 7.0.3 + 7.0.4 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 112a45e7580..2316cf6c77b 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,12 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 484d8714faa..2f55a6f9426 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 7.0.3 + 7.0.4 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index c66a4cc76cf..a2e4a96afae 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 92f9ba96f88..78f8a2a45fd 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 7.0.3 + 7.0.4 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 3b56d58375c..874579d5052 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 4c9ed5482c3..773bfe663d2 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 7.0.3 + 7.0.4 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 36d4f266144..5adaf81ff87 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,16 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge pull request `#1486 `_ from tier4/fix/speed-condition/backward-compatibility + Fix/speed condition/backward compatibility +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Add new parameter `speed_condition` to switch compatibility +* Add new enumeration `Compatibility` +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index e9fbe1d3598..0826de6a98e 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 7.0.3 + 7.0.4 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 3038b9e4678..c59120080dc 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 4a31ce56fd8..6ef4c36cf6b 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 7.0.3 + 7.0.4 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index f45a5099e19..b7582bd5a37 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 56a95035ba2..3fc90d56bd8 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 7.0.3 + 7.0.4 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 674191360dc..6b36a4fa0ad 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index e91d6109b6e..1bf43109ae3 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 7.0.3 + 7.0.4 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 4d4702d540a..9717e5fea04 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index d044251414e..db4ca60757b 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 7.0.3 + 7.0.4 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 06c7e90f7dc..5cec18c57ca 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,12 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index b8c23e528f9..234952f2623 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 7.0.3 + 7.0.4 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 68c811fe173..8c73f295169 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,12 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 19840b64144..5a538f788b6 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 7.0.3 + 7.0.4 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index f53adfee34f..cb44766923a 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index a02db4e9fbd..d479f37b4e2 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 7.0.3 + 7.0.4 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index fabf001a247..75789efcfb8 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index bce21f3ee2e..d61120a1ad3 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 7.0.3 + 7.0.4 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index bace7285cff..84967884d80 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 54211af4af7..55e95745d6b 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 7.0.3 + 7.0.4 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index c03dd28c38d..4c1534e2e20 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 640aea992d0..954652386e3 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 7.0.3 + 7.0.4 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index a2df026aa25..9c4c1b21250 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 937e3a5441e..fde03aea3b1 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 7.0.3 + 7.0.4 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 6727d05b83f..5332076f875 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 1e1d5e3cb84..2c3a32bfbb6 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 7.0.3 + 7.0.4 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 26d57436298..4cf0429c43a 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 046efa14c6a..a75f30edfd2 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 7.0.3 + 7.0.4 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index a3e40444e82..e19f2963a66 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge pull request `#1465 `_ from tier4/fix/request-enable-autoware-control diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index d3ceb5ed4f8..3830901f7ca 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 7.0.3 + 7.0.4 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 11b944a5910..0d1035446d0 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index a872b522734..c4fb5beafc4 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 7.0.3 + 7.0.4 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index bb5ba5043d1..c8e5351fe86 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 0d8796c11b3..5c01ea5269a 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 7.0.3 + 7.0.4 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 150fe57fb3b..7ea86322917 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,16 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.0.4 (2024-12-13) +------------------ +* Merge pull request `#1486 `_ from tier4/fix/speed-condition/backward-compatibility + Fix/speed condition/backward compatibility +* Merge branch 'master' into fix/speed-condition/backward-compatibility +* Merge remote-tracking branch 'origin/master' into fix/speed-condition/backward-compatibility +* Add new parameter `speed_condition` to switch compatibility +* Add new enumeration `Compatibility` +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.3 (2024-12-13) ------------------ * Merge branch 'master' into fix/request-enable-autoware-control diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 419a1b7fc01..633d1aeaf30 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 7.0.3 + 7.0.4 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 1717315cebb72362ba915681735b595956c1c1b5 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 13 Dec 2024 14:14:46 +0900 Subject: [PATCH 47/54] 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 From eaaa87307b7a50c48caef02386f9bc86e9e62e31 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Mon, 16 Dec 2024 01:51:33 +0000 Subject: [PATCH 48/54] Bump version of scenario_simulator_v2 from version 7.0.4 to version 7.1.0 --- common/math/arithmetic/CHANGELOG.rst | 40 +++++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 42 ++++++++++++ common/math/geometry/package.xml | 2 +- .../CHANGELOG.rst | 40 +++++++++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 40 +++++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 40 +++++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 40 +++++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 40 +++++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 40 +++++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 36 ++++++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 40 +++++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 40 +++++++++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 66 +++++++++++++++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 40 +++++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 40 +++++++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 40 +++++++++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 40 +++++++++++ .../package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 40 +++++++++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 40 +++++++++++ .../openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 40 +++++++++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 40 +++++++++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 40 +++++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 40 +++++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 40 +++++++++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 41 ++++++++++++ .../simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 41 ++++++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 41 ++++++++++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 40 +++++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 40 +++++++++++ test_runner/random_test_runner/package.xml | 2 +- .../scenario_test_runner/CHANGELOG.rst | 49 ++++++++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 1225 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 4bb19449115..355630f0aa1 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 15abfa02a91..0f4f5822ab2 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 7.0.4 + 7.1.0 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 7978b669400..12bb5ca7850 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,48 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Cleanup +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Add new static member function `RelativeSpeedCondition::evaluate` +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 49467cbde14..1e4ac8f3174 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 7.0.4 + 7.1.0 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index fb9d82f2305..534aa3a16e2 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge pull request `#1486 `_ from tier4/fix/speed-condition/backward-compatibility diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index d82aec6de9a..5700054a3f0 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 7.0.4 + 7.1.0 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index b460aa61a8e..f4413aa3c34 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 0453c2ae9b0..8c42e8e9e09 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 7.0.4 + 7.1.0 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index d83fa605d55..790c6f6d386 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 30e322eb56e..86a54b73946 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 7.0.4 + 7.1.0 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index d1cd7fcce35..4fac7e94197 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 703a5b23184..79bd0769e2b 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 7.0.4 + 7.1.0 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 1f1f5bc5223..86d104903de 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,46 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index f68ffcd128d..2636408c83b 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 7.0.4 + 7.1.0 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 852f27c951a..e50bf4e39bc 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index c111cd34b59..4a000c33aae 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 7.0.4 + 7.1.0 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 2316cf6c77b..a3cc2c3c282 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,42 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 2f55a6f9426..c3c6ef75696 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 7.0.4 + 7.1.0 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index a2e4a96afae..93dd7c74d96 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 78f8a2a45fd..c0f4a5c6f09 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 7.0.4 + 7.1.0 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 874579d5052..6a1f395a39a 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 773bfe663d2..dcb2b66398f 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 7.0.4 + 7.1.0 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 5adaf81ff87..331e3c798ab 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,72 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge pull request `#1258 `_ from tier4/feature/time-to-collision-condition + Feature/time to collision condition +* Update `TimeToCollisionCondition` to call `SpeedCondition` in standard compatible mode +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Remove static member function `evaluateTimeToCollisionCondition` +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Cleanup +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Fix `evaluateTimeToCollisionCondition` to not return meaningless value when collisions cannot occur +* Fix `TimeToCollisionCondition` to return inf if relative speed < zero +* Cleanup static member function `TimeToCollisionCondition::evaluate` +* Add new member function `evaluateCartesianTimeToCollisionCondition` +* Split `(Relative)?DistanceCondition::evaluate` into two overloads +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Add new static member function `TimeToCollisionCondition::evaluate` +* Update `unordered_map` of the `Entities` base class to private +* Move function `hypot` into new header `cmath/hypot.hpp` +* Add support for `DirectionalDimension` to `SpeedCondition` +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Rename `(Relative)?DistanceCondition::distance` to `evaluate` +* Update member function `CoordinateSystem::distance` to be static member +* Add `const Position &` to the argument of `DistanceCondition::distance` +* Remove data member `DistanceCondition::consider_z` +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Add new static member function `RelativeSpeedCondition::evaluate` +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Update `RelativeDistanceCondition::distance` to static member function +* Move entity existence check into `distance` from speceialized `distance` +* Add static member function `ConditionEvaluation::evaluateRelativeSpeed` +* Add new structs `RelativeSpeedCondition` and `DirectionalDimension` +* Add new struct `TimeToCollisionConditionTarget` +* Add new struct `TimeToCollisionCondition` +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge pull request `#1486 `_ from tier4/fix/speed-condition/backward-compatibility diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 0826de6a98e..1259b887e80 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 7.0.4 + 7.1.0 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index c59120080dc..fff205ca57e 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 6ef4c36cf6b..3588d2cf659 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 7.0.4 + 7.1.0 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index b7582bd5a37..b91ae12d68a 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 3fc90d56bd8..d9f8bef9dd8 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 7.0.4 + 7.1.0 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 6b36a4fa0ad..fb82d84754f 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 1bf43109ae3..e6c39298a41 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 7.0.4 + 7.1.0 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 9717e5fea04..87336ec580a 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index db4ca60757b..ad8f0ee9415 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 7.0.4 + 7.1.0 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 5cec18c57ca..c6540820fcf 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,46 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 234952f2623..67a482c5a1f 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 7.0.4 + 7.1.0 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 8c73f295169..ef065925903 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,46 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 5a538f788b6..843a4d451fc 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 7.0.4 + 7.1.0 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index cb44766923a..ff94ea238a5 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index d479f37b4e2..e4667786798 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 7.0.4 + 7.1.0 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 75789efcfb8..2e532270d06 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index d61120a1ad3..df48d20cc04 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 7.0.4 + 7.1.0 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 84967884d80..d51161d48c2 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 55e95745d6b..3e386ff0784 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 7.0.4 + 7.1.0 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 4c1534e2e20..bddb30514b1 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 954652386e3..86af7944595 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 7.0.4 + 7.1.0 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 9c4c1b21250..36249354679 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index fde03aea3b1..25819c44f65 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 7.0.4 + 7.1.0 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 5332076f875..6e96e2f25fa 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,47 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 2c3a32bfbb6..1ab93e383ff 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 7.0.4 + 7.1.0 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 4cf0429c43a..f306ba75dff 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,47 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index a75f30edfd2..7a2bb0820a2 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 7.0.4 + 7.1.0 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index e19f2963a66..ed7cebbb41f 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,47 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 3830901f7ca..98e152d4b78 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 7.0.4 + 7.1.0 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 0d1035446d0..bf7f1b1871c 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index c4fb5beafc4..4cd1e20519e 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 7.0.4 + 7.1.0 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index c8e5351fe86..74287ab308c 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,46 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge branch 'master' into fix/speed-condition/backward-compatibility diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 5c01ea5269a..6bf18a22f48 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 7.0.4 + 7.1.0 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 7ea86322917..ce6500b2e13 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,55 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.1.0 (2024-12-16) +------------------ +* Merge pull request `#1258 `_ from tier4/feature/time-to-collision-condition + Feature/time to collision condition +* Update `TimeToCollisionCondition` to call `SpeedCondition` in standard compatible mode +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Remove static member function `evaluateTimeToCollisionCondition` +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Fix `evaluateTimeToCollisionCondition` to not return meaningless value when collisions cannot occur +* Fix `TimeToCollisionCondition` to return inf if relative speed < zero +* Cleanup static member function `TimeToCollisionCondition::evaluate` +* Add new test scenario `...EntityCondition.TimeToCollisionCondition.yaml` +* Add new member function `evaluateCartesianTimeToCollisionCondition` +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Merge branch 'master' into feature/time-to-collision-condition +* Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.0.4 (2024-12-13) ------------------ * Merge pull request `#1486 `_ from tier4/fix/speed-condition/backward-compatibility diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 633d1aeaf30..5edd5d15bc3 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 7.0.4 + 7.1.0 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 51c8951e047b43a4cd5aa27df577674f20cf74c4 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Mon, 16 Dec 2024 11:31:22 +0900 Subject: [PATCH 49/54] Add `/localization/pose_estimator/pose_with_covariance` to `Communication.md` Signed-off-by: yamacir-kit --- docs/developer_guide/Communication.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/docs/developer_guide/Communication.md b/docs/developer_guide/Communication.md index 48d22522178..1000197d55e 100644 --- a/docs/developer_guide/Communication.md +++ b/docs/developer_guide/Communication.md @@ -23,8 +23,9 @@ |------------------------------------------------------------------|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|-----------------------------------------------------------------------------------------------------------------------------------------------------------------------| | `/clock` | [`rcl_interfaces/msg/Clock`](https://github.com/ros2/rcl_interfaces/blob/master/rosgraph_msgs/msg/Clock.msg) | | | | | `/initialpose` | [`geometry_msgs/msg/PoseWithCovarianceStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | | -| `/localization/kinematic_state` | [`nav_msgs/msg/Odometry`](https://github.com/ros2/common_interfaces/blob/master/nav_msgs/msg/Odometry.msg) | | -| `/localization/acceleration` | [`geometry_msgs::msg::AccelWithCovarianceStamped`](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | | +| `/localization/kinematic_state` | [`nav_msgs/msg/Odometry`](https://github.com/ros2/common_interfaces/blob/master/nav_msgs/msg/Odometry.msg) | Available if option `simulate_localization` is `true` (default is `true`). | +| `/localization/acceleration` | [`geometry_msgs::msg::AccelWithCovarianceStamped`](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Available if option `simulate_localization` is `true` (default is `true`). | +| `/localization/pose_estimator/pose_with_covariance` | [`geometry_msgs/msg/PoseWithCovarianceStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Available if option `simulate_localization` is `false` (default is `true`). | | `/planning/mission_planning/checkpoint` | [`geometry_msgs/msg/PoseStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseStamped.msg) | | | `/planning/mission_planning/goal` | [`geometry_msgs/msg/PoseStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseStamped.msg) | | | `/vehicle/status/control_mode` | [`autoware_vehicle_msgs/msg/ControlModeReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/ControlModeReport.msg) | | From 32a8189b80b6a076c455068995bf5b083da0e4a2 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Mon, 16 Dec 2024 11:41:52 +0900 Subject: [PATCH 50/54] Reformat tables in `Communication.md` Signed-off-by: yamacir-kit --- docs/developer_guide/Communication.md | 58 +++++++++++++-------------- 1 file changed, 29 insertions(+), 29 deletions(-) diff --git a/docs/developer_guide/Communication.md b/docs/developer_guide/Communication.md index 1000197d55e..12b686d824c 100644 --- a/docs/developer_guide/Communication.md +++ b/docs/developer_guide/Communication.md @@ -11,39 +11,39 @@ | `/control/command/turn_indicators_cmd` | [`autoware_vehicle_msgs/msg/TurnIndicatorsCommand`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/TurnIndicatorsCommand.msg) | Used in UserDefinedValueCondition : `currentTurnIndicatorsState` | | `/parameter_events` | [`rcl_interfaces/msg/ParameterEvent`](https://github.com/ros2/rcl_interfaces/blob/master/rcl_interfaces/msg/ParameterEvent.msg) | | | `/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id` | [`tier4_planning_msgs/msg/PathWithLaneId`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_planning_msgs/msg/PathWithLaneId.msg) | | -| `/api/iv_msgs/planning/scenario_planning/trajectory` | [`tier4_planning_msgs/msg/Trajectory`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_planning_msgs/msg/Trajectory.msg) | | -| `/api/external/get/emergency` | [`tier4_external_api_msgs/msg/Emergency`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_external_api_msgs/msg/Emergency.msg) | Used in UserDefinedValueCondition : `currentEmergencyState` | +| `/api/iv_msgs/planning/scenario_planning/trajectory` | [`tier4_planning_msgs/msg/Trajectory`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_planning_msgs/msg/Trajectory.msg) | | +| `/api/external/get/emergency` | [`tier4_external_api_msgs/msg/Emergency`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_external_api_msgs/msg/Emergency.msg) | Used in UserDefinedValueCondition : `currentEmergencyState` | | `/api/fail_safe/mrm_state` | [`autoware_adapi_v1_msgs/msg/MrmState`](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/system/msg/MrmState.msg) | Used in UserDefinedValueCondition : `currentMinimumRiskManeuverState` | -| `/planning/scenario_planning/motion_velocity_optimizer/closest_jerk` | [`tier4_debug_msgs/msg/Float32Stamped`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_debug_msgs/msg/Float32Stamped.msg) | Used in /simulation/openscenario_interpreter | -| `/api/external/get/rtc_status` | [`tier4_rtc_msgs::msg::CooperateStatusArray`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_rtc_msgs/msg/CooperateStatusArray.msg) | | +| `/planning/scenario_planning/motion_velocity_optimizer/closest_jerk` | [`tier4_debug_msgs/msg/Float32Stamped`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_debug_msgs/msg/Float32Stamped.msg) | Used in `/simulation/openscenario_interpreter` | +| `/api/external/get/rtc_status` | [`tier4_rtc_msgs/msg/CooperateStatusArray`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_rtc_msgs/msg/CooperateStatusArray.msg) | | ### Publishers -| topic | type | note | -|------------------------------------------------------------------|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|-----------------------------------------------------------------------------------------------------------------------------------------------------------------------| -| `/clock` | [`rcl_interfaces/msg/Clock`](https://github.com/ros2/rcl_interfaces/blob/master/rosgraph_msgs/msg/Clock.msg) | | | | -| `/initialpose` | [`geometry_msgs/msg/PoseWithCovarianceStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | | -| `/localization/kinematic_state` | [`nav_msgs/msg/Odometry`](https://github.com/ros2/common_interfaces/blob/master/nav_msgs/msg/Odometry.msg) | Available if option `simulate_localization` is `true` (default is `true`). | -| `/localization/acceleration` | [`geometry_msgs::msg::AccelWithCovarianceStamped`](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Available if option `simulate_localization` is `true` (default is `true`). | -| `/localization/pose_estimator/pose_with_covariance` | [`geometry_msgs/msg/PoseWithCovarianceStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Available if option `simulate_localization` is `false` (default is `true`). | -| `/planning/mission_planning/checkpoint` | [`geometry_msgs/msg/PoseStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseStamped.msg) | | -| `/planning/mission_planning/goal` | [`geometry_msgs/msg/PoseStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseStamped.msg) | | -| `/vehicle/status/control_mode` | [`autoware_vehicle_msgs/msg/ControlModeReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/ControlModeReport.msg) | | -| `/vehicle/status/gear_status` | [`autoware_vehicle_msgs/msg/GearReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/GearReport.msg) | | -| `/vehicle/status/steering_status` | [`autoware_vehicle_msgs/msg/SteeringReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/SteeringReport.msg) | | -| `/vehicle/status/turn_indicators_status` | [`autoware_vehicle_msgs/msg/TurnIndicatorsReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/TurnIndicatorsReport.msg) | | -| `/vehicle/status/velocity_status` | [`autoware_vehicle_msgs/msg/VelocityReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/VelocityReport.msg) | | -| `/perception/object_recognition/detection/objects` | [`autoware_perception_msgs/msg/DetectedObjects`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/DetectedObjects.msg) | [Simulated by simple_sensor_simulator](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#object-detection-results-simulation) | -| `/perception/object_recognition/ground_truth/objects` | [`autoware_perception_msgs/msg/TrackedObjects`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrackedObjects.msg) | [Simulated by simple_sensor_simulator](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#object-detection-results-simulation) | -| `/perception/obstacle_segmentation/pointcloud` | [`sensor_msgs/msg/PointCloud2`](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/PointCloud2.msg) | [Simulated by simple_sensor_simulator](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#lidar-simulation) | -| `/perception/occupancy_grid_map/map` | [`nav_msgs/msg/OccupancyGrid`](https://github.com/ros2/common_interfaces/blob/master/nav_msgs/msg/OccupancyGrid.msg) | [Simulated by simple_sensor_simulator](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#occupancy-grid-sensor-simulation) | -| `/sensing/imu/imu_data` | [`sensor_msgs/msg/Imu`](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/Imu.msg) | | -| `/perception/traffic_light_recognition/internal/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | Optical traffic light interface for `architecture_type` equal to `awf/universe/20230906` | -| `/perception/traffic_light_recognition/internal/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Optical traffic light interface for `architecture_type` equal to `awf/universe/20240605` | -| `/perception/traffic_light_recognition/external/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | V2I traffic light interface for `architecture_type` equal to `awf/universe/20230906` | -| `/perception/traffic_light_recognition/external/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | V2I traffic light interface for `architecture_type` equal to `awf/universe/20240605` | -| `/v2x/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | Additional V2I traffic light interface for `architecture_type` equal to `awf/universe/20230906` | -| `/v2x/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Additional V2I traffic light interface for `architecture_type` equal to `awf/universe/20240605` | +| topic | type | note | +|------------------------------------------------------------------|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| `/clock` | [`rcl_interfaces/msg/Clock`](https://github.com/ros2/rcl_interfaces/blob/master/rosgraph_msgs/msg/Clock.msg) | | | | +| `/initialpose` | [`geometry_msgs/msg/PoseWithCovarianceStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | | +| `/localization/kinematic_state` | [`nav_msgs/msg/Odometry`](https://github.com/ros2/common_interfaces/blob/master/nav_msgs/msg/Odometry.msg) | Available if option `simulate_localization` is `true` (default is `true`). | +| `/localization/acceleration` | [`geometry_msgs/msg/AccelWithCovarianceStamped`](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Available if option `simulate_localization` is `true` (default is `true`). | +| `/localization/pose_estimator/pose_with_covariance` | [`geometry_msgs/msg/PoseWithCovarianceStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Available if option `simulate_localization` is `false` (default is `true`). | +| `/planning/mission_planning/checkpoint` | [`geometry_msgs/msg/PoseStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseStamped.msg) | | +| `/planning/mission_planning/goal` | [`geometry_msgs/msg/PoseStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseStamped.msg) | | +| `/vehicle/status/control_mode` | [`autoware_vehicle_msgs/msg/ControlModeReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/ControlModeReport.msg) | | +| `/vehicle/status/gear_status` | [`autoware_vehicle_msgs/msg/GearReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/GearReport.msg) | | +| `/vehicle/status/steering_status` | [`autoware_vehicle_msgs/msg/SteeringReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/SteeringReport.msg) | | +| `/vehicle/status/turn_indicators_status` | [`autoware_vehicle_msgs/msg/TurnIndicatorsReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/TurnIndicatorsReport.msg) | | +| `/vehicle/status/velocity_status` | [`autoware_vehicle_msgs/msg/VelocityReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/VelocityReport.msg) | | +| `/perception/object_recognition/detection/objects` | [`autoware_perception_msgs/msg/DetectedObjects`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/DetectedObjects.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#object-detection-results-simulation) | +| `/perception/object_recognition/ground_truth/objects` | [`autoware_perception_msgs/msg/TrackedObjects`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrackedObjects.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#object-detection-results-simulation) | +| `/perception/obstacle_segmentation/pointcloud` | [`sensor_msgs/msg/PointCloud2`](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/PointCloud2.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#lidar-simulation) | +| `/perception/occupancy_grid_map/map` | [`nav_msgs/msg/OccupancyGrid`](https://github.com/ros2/common_interfaces/blob/master/nav_msgs/msg/OccupancyGrid.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#occupancy-grid-sensor-simulation) | +| `/sensing/imu/imu_data` | [`sensor_msgs/msg/Imu`](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/Imu.msg) | | +| `/perception/traffic_light_recognition/internal/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | Optical traffic light interface for `architecture_type` equal to `awf/universe/20230906` | +| `/perception/traffic_light_recognition/internal/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Optical traffic light interface for `architecture_type` equal to `awf/universe/20240605` | +| `/perception/traffic_light_recognition/external/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | V2I traffic light interface for `architecture_type` equal to `awf/universe/20230906` | +| `/perception/traffic_light_recognition/external/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | V2I traffic light interface for `architecture_type` equal to `awf/universe/20240605` | +| `/v2x/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | Additional V2I traffic light interface for `architecture_type` equal to `awf/universe/20230906` | +| `/v2x/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Additional V2I traffic light interface for `architecture_type` equal to `awf/universe/20240605` | [//]: # (| /rosout | rcl_interfaces/msg/Log | | |) [//]: # (| /tf | tf2_msgs/msg/TFMessage | | |) From 916ba5bee50836b84d71c3e3076b8408524e884a Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Mon, 16 Dec 2024 11:48:17 +0900 Subject: [PATCH 51/54] Sort the table lexicographically by topic name Signed-off-by: yamacir-kit --- docs/developer_guide/Communication.md | 38 +++++++++++++-------------- 1 file changed, 19 insertions(+), 19 deletions(-) diff --git a/docs/developer_guide/Communication.md b/docs/developer_guide/Communication.md index 12b686d824c..1927ae5ee8a 100644 --- a/docs/developer_guide/Communication.md +++ b/docs/developer_guide/Communication.md @@ -5,17 +5,17 @@ | topic | type | note | |--------------------------------------------------------------------------------|------------------------------------------------------------------------------------------------------------------------------------------------------------------------|-----------------------------------------------------------------------| -| `/autoware/state` | [`autoware_system_msgs/msg/AutowareState`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_system_msgs/msg/AutowareState.msg) | Used in UserDefinedValueCondition : `currentAutowareState` | +| `/api/external/get/emergency` | [`tier4_external_api_msgs/msg/Emergency`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_external_api_msgs/msg/Emergency.msg) | Used in UserDefinedValueCondition `currentEmergencyState` | +| `/api/external/get/rtc_status` | [`tier4_rtc_msgs/msg/CooperateStatusArray`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_rtc_msgs/msg/CooperateStatusArray.msg) | | +| `/api/fail_safe/mrm_state` | [`autoware_adapi_v1_msgs/msg/MrmState`](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/system/msg/MrmState.msg) | Used in UserDefinedValueCondition `currentMinimumRiskManeuverState` | +| `/api/iv_msgs/planning/scenario_planning/trajectory` | [`tier4_planning_msgs/msg/Trajectory`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_planning_msgs/msg/Trajectory.msg) | | +| `/autoware/state` | [`autoware_system_msgs/msg/AutowareState`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_system_msgs/msg/AutowareState.msg) | Used in UserDefinedValueCondition `currentAutowareState` | | `/control/command/control_cmd` | [`autoware_control_msgs/msg/Control`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_control_msgs/msg/Control.msg) | | | `/control/command/gear_cmd` | [`autoware_vehicle_msgs/msg/GearCommand`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/GearCommand.msg) | | -| `/control/command/turn_indicators_cmd` | [`autoware_vehicle_msgs/msg/TurnIndicatorsCommand`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/TurnIndicatorsCommand.msg) | Used in UserDefinedValueCondition : `currentTurnIndicatorsState` | +| `/control/command/turn_indicators_cmd` | [`autoware_vehicle_msgs/msg/TurnIndicatorsCommand`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/TurnIndicatorsCommand.msg) | Used in UserDefinedValueCondition `currentTurnIndicatorsState` | | `/parameter_events` | [`rcl_interfaces/msg/ParameterEvent`](https://github.com/ros2/rcl_interfaces/blob/master/rcl_interfaces/msg/ParameterEvent.msg) | | | `/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id` | [`tier4_planning_msgs/msg/PathWithLaneId`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_planning_msgs/msg/PathWithLaneId.msg) | | -| `/api/iv_msgs/planning/scenario_planning/trajectory` | [`tier4_planning_msgs/msg/Trajectory`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_planning_msgs/msg/Trajectory.msg) | | -| `/api/external/get/emergency` | [`tier4_external_api_msgs/msg/Emergency`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_external_api_msgs/msg/Emergency.msg) | Used in UserDefinedValueCondition : `currentEmergencyState` | -| `/api/fail_safe/mrm_state` | [`autoware_adapi_v1_msgs/msg/MrmState`](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/system/msg/MrmState.msg) | Used in UserDefinedValueCondition : `currentMinimumRiskManeuverState` | | `/planning/scenario_planning/motion_velocity_optimizer/closest_jerk` | [`tier4_debug_msgs/msg/Float32Stamped`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_debug_msgs/msg/Float32Stamped.msg) | Used in `/simulation/openscenario_interpreter` | -| `/api/external/get/rtc_status` | [`tier4_rtc_msgs/msg/CooperateStatusArray`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_rtc_msgs/msg/CooperateStatusArray.msg) | | ### Publishers @@ -23,27 +23,27 @@ |------------------------------------------------------------------|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------------| | `/clock` | [`rcl_interfaces/msg/Clock`](https://github.com/ros2/rcl_interfaces/blob/master/rosgraph_msgs/msg/Clock.msg) | | | | | `/initialpose` | [`geometry_msgs/msg/PoseWithCovarianceStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | | -| `/localization/kinematic_state` | [`nav_msgs/msg/Odometry`](https://github.com/ros2/common_interfaces/blob/master/nav_msgs/msg/Odometry.msg) | Available if option `simulate_localization` is `true` (default is `true`). | | `/localization/acceleration` | [`geometry_msgs/msg/AccelWithCovarianceStamped`](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Available if option `simulate_localization` is `true` (default is `true`). | +| `/localization/kinematic_state` | [`nav_msgs/msg/Odometry`](https://github.com/ros2/common_interfaces/blob/master/nav_msgs/msg/Odometry.msg) | Available if option `simulate_localization` is `true` (default is `true`). | | `/localization/pose_estimator/pose_with_covariance` | [`geometry_msgs/msg/PoseWithCovarianceStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Available if option `simulate_localization` is `false` (default is `true`). | +| `/perception/object_recognition/detection/objects` | [`autoware_perception_msgs/msg/DetectedObjects`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/DetectedObjects.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#object-detection-results-simulation) | +| `/perception/object_recognition/ground_truth/objects` | [`autoware_perception_msgs/msg/TrackedObjects`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrackedObjects.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#object-detection-results-simulation) | +| `/perception/obstacle_segmentation/pointcloud` | [`sensor_msgs/msg/PointCloud2`](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/PointCloud2.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#lidar-simulation) | +| `/perception/occupancy_grid_map/map` | [`nav_msgs/msg/OccupancyGrid`](https://github.com/ros2/common_interfaces/blob/master/nav_msgs/msg/OccupancyGrid.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#occupancy-grid-sensor-simulation) | +| `/perception/traffic_light_recognition/external/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | V2I traffic light interface for `architecture_type` equal to `awf/universe/20240605` | +| `/perception/traffic_light_recognition/external/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | V2I traffic light interface for `architecture_type` equal to `awf/universe/20230906` | +| `/perception/traffic_light_recognition/internal/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Optical traffic light interface for `architecture_type` equal to `awf/universe/20240605` | +| `/perception/traffic_light_recognition/internal/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | Optical traffic light interface for `architecture_type` equal to `awf/universe/20230906` | | `/planning/mission_planning/checkpoint` | [`geometry_msgs/msg/PoseStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseStamped.msg) | | | `/planning/mission_planning/goal` | [`geometry_msgs/msg/PoseStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseStamped.msg) | | +| `/sensing/imu/imu_data` | [`sensor_msgs/msg/Imu`](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/Imu.msg) | | +| `/v2x/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Additional V2I traffic light interface for `architecture_type` equal to `awf/universe/20240605` | +| `/v2x/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | Additional V2I traffic light interface for `architecture_type` equal to `awf/universe/20230906` | | `/vehicle/status/control_mode` | [`autoware_vehicle_msgs/msg/ControlModeReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/ControlModeReport.msg) | | | `/vehicle/status/gear_status` | [`autoware_vehicle_msgs/msg/GearReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/GearReport.msg) | | | `/vehicle/status/steering_status` | [`autoware_vehicle_msgs/msg/SteeringReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/SteeringReport.msg) | | | `/vehicle/status/turn_indicators_status` | [`autoware_vehicle_msgs/msg/TurnIndicatorsReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/TurnIndicatorsReport.msg) | | | `/vehicle/status/velocity_status` | [`autoware_vehicle_msgs/msg/VelocityReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/VelocityReport.msg) | | -| `/perception/object_recognition/detection/objects` | [`autoware_perception_msgs/msg/DetectedObjects`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/DetectedObjects.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#object-detection-results-simulation) | -| `/perception/object_recognition/ground_truth/objects` | [`autoware_perception_msgs/msg/TrackedObjects`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrackedObjects.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#object-detection-results-simulation) | -| `/perception/obstacle_segmentation/pointcloud` | [`sensor_msgs/msg/PointCloud2`](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/PointCloud2.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#lidar-simulation) | -| `/perception/occupancy_grid_map/map` | [`nav_msgs/msg/OccupancyGrid`](https://github.com/ros2/common_interfaces/blob/master/nav_msgs/msg/OccupancyGrid.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#occupancy-grid-sensor-simulation) | -| `/sensing/imu/imu_data` | [`sensor_msgs/msg/Imu`](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/Imu.msg) | | -| `/perception/traffic_light_recognition/internal/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | Optical traffic light interface for `architecture_type` equal to `awf/universe/20230906` | -| `/perception/traffic_light_recognition/internal/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Optical traffic light interface for `architecture_type` equal to `awf/universe/20240605` | -| `/perception/traffic_light_recognition/external/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | V2I traffic light interface for `architecture_type` equal to `awf/universe/20230906` | -| `/perception/traffic_light_recognition/external/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | V2I traffic light interface for `architecture_type` equal to `awf/universe/20240605` | -| `/v2x/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | Additional V2I traffic light interface for `architecture_type` equal to `awf/universe/20230906` | -| `/v2x/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Additional V2I traffic light interface for `architecture_type` equal to `awf/universe/20240605` | [//]: # (| /rosout | rcl_interfaces/msg/Log | | |) [//]: # (| /tf | tf2_msgs/msg/TFMessage | | |) @@ -55,8 +55,8 @@ |-----------------------------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|------| | `/api/autoware/set/velocity_limit` | [`tier4_external_api_msgs/srv/SetVelocityLimit`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_external_api_msgs/srv/SetVelocityLimit.srv) | | | `/api/external/set/engage` | [`tier4_external_api_msgs/srv/Engage`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_external_api_msgs/srv/Engage.srv) | | -| `/api/external/set/rtc_commands` | [`tier4_rtc_msgs/srv/CooperateCommands`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_rtc_msgs/srv/CooperateCommands.srv) | | | `/api/external/set/rtc_auto_mode` | [`tier4_rtc_msgs/srv/AutoModeWithModule`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_rtc_msgs/srv/AutoModeWithModule.srv) | | +| `/api/external/set/rtc_commands` | [`tier4_rtc_msgs/srv/CooperateCommands`](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_rtc_msgs/srv/CooperateCommands.srv) | | | `/api/operation_mode/enable_autoware_control` | [`autoware_adapi_v1_msgs/srv/ChangeOperationMode`](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/operation_mode/srv/ChangeOperationMode.srv) | | ### Service Servers From ce9295291acc11a9187be7b9538c4276eb5d56d3 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Mon, 16 Dec 2024 11:50:15 +0900 Subject: [PATCH 52/54] Remove comments in `Communication.md` Signed-off-by: yamacir-kit --- docs/developer_guide/Communication.md | 16 ---------------- 1 file changed, 16 deletions(-) diff --git a/docs/developer_guide/Communication.md b/docs/developer_guide/Communication.md index 1927ae5ee8a..1da73ed82f0 100644 --- a/docs/developer_guide/Communication.md +++ b/docs/developer_guide/Communication.md @@ -45,10 +45,6 @@ | `/vehicle/status/turn_indicators_status` | [`autoware_vehicle_msgs/msg/TurnIndicatorsReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/TurnIndicatorsReport.msg) | | | `/vehicle/status/velocity_status` | [`autoware_vehicle_msgs/msg/VelocityReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/VelocityReport.msg) | | -[//]: # (| /rosout | rcl_interfaces/msg/Log | | |) -[//]: # (| /tf | tf2_msgs/msg/TFMessage | | |) -[//]: # (| /parameter_events | rcl_interfaces/msg/ParameterEvent | | |) - ### Service Clients | service name | type | note | @@ -64,15 +60,3 @@ | service name | type | note | |---------------------------------|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------|--------------------------------------------------------------| | `/control/control_mode_request` | [`autoware_auto_vehicle_msgs/srv/ControlModeCommand`](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/srv/ControlModeCommand.srv) | Simulated by `simple_sensor_simulator` for a manual override | - -[//]: # (/simulation/openscenario_visualizer) - -[//]: # (Subscribers:) - -[//]: # (/simulation/entity/status: traffic_simulator_msgs/msg/EntityStatusWithTrajectoryArray) - -[//]: # (Publishers:) - -[//]: # (/simulation/entity/marker: visualization_msgs/msg/MarkerArray) - -[//]: # () From 6d8ce96ca3a74c06447183df78644c9a94c636f5 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Mon, 16 Dec 2024 05:41:38 +0000 Subject: [PATCH 53/54] Bump version of scenario_simulator_v2 from version 7.1.0 to version 7.2.0 --- common/math/arithmetic/CHANGELOG.rst | 15 +++++++++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 15 +++++++++++++++ common/math/geometry/package.xml | 2 +- .../CHANGELOG.rst | 15 +++++++++++++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 15 +++++++++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 15 +++++++++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 19 +++++++++++++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 15 +++++++++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 15 +++++++++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 15 +++++++++++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 15 +++++++++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 15 +++++++++++++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 16 ++++++++++++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 15 +++++++++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 15 +++++++++++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 15 +++++++++++++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 15 +++++++++++++++ .../package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 15 +++++++++++++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 15 +++++++++++++++ .../openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 15 +++++++++++++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 15 +++++++++++++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 15 +++++++++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 15 +++++++++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 15 +++++++++++++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 18 ++++++++++++++++++ .../simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 15 +++++++++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 18 ++++++++++++++++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 15 +++++++++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 15 +++++++++++++++ test_runner/random_test_runner/package.xml | 2 +- .../scenario_test_runner/CHANGELOG.rst | 19 +++++++++++++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 479 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 355630f0aa1..00157438e0a 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 0f4f5822ab2..eb64a9ff504 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 7.1.0 + 7.2.0 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 12bb5ca7850..ada9a6569bf 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 1e4ac8f3174..4e6a717ea81 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 7.1.0 + 7.2.0 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 534aa3a16e2..887c77f337e 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 5700054a3f0..53da81744bd 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 7.1.0 + 7.2.0 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index f4413aa3c34..886ac0d4264 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 8c42e8e9e09..022f47d3339 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 7.1.0 + 7.2.0 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 790c6f6d386..d35ce5574fd 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 86a54b73946..5fc64409eef 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 7.1.0 + 7.2.0 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 4fac7e94197..4cd7cc43996 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,25 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge pull request `#1484 `_ from tier4/RJD-736/autoware_msgs_support_and_localization_sim_mode_support + Rjd 736/autoware msgs support and localization sim mode support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Add the missing semicolon +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Add launch argument `simulate_localization` to `scenario_test_runner` +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 79bd0769e2b..6308636521d 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 7.1.0 + 7.2.0 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 86d104903de..173ae3e0eb5 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,21 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 2636408c83b..cf8c7245b1a 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 7.1.0 + 7.2.0 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index e50bf4e39bc..1663efd54b0 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 4a000c33aae..66c98fb29bd 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 7.1.0 + 7.2.0 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index a3cc2c3c282..b9ea513a641 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,21 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index c3c6ef75696..35b7d07eaf6 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 7.1.0 + 7.2.0 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 93dd7c74d96..d7691f345b9 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index c0f4a5c6f09..640155968db 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 7.1.0 + 7.2.0 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 6a1f395a39a..ef2dfbdd120 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index dcb2b66398f..a834e1e4b59 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 7.1.0 + 7.2.0 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 331e3c798ab..bc48149ebdb 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,22 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge pull request `#1258 `_ from tier4/feature/time-to-collision-condition diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 1259b887e80..5f555daba8b 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 7.1.0 + 7.2.0 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index fff205ca57e..ed1774681db 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 3588d2cf659..b5ac17c1c0b 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 7.1.0 + 7.2.0 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index b91ae12d68a..581c13a2606 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index d9f8bef9dd8..c2a5042dd7c 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 7.1.0 + 7.2.0 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index fb82d84754f..e69a8044f83 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index e6c39298a41..ab58136c7f3 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 7.1.0 + 7.2.0 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 87336ec580a..4c0231e37d7 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index ad8f0ee9415..21b1247bd37 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 7.1.0 + 7.2.0 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index c6540820fcf..317b0449bc7 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,21 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 67a482c5a1f..88fd01322dc 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 7.1.0 + 7.2.0 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index ef065925903..dfcbe41993a 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,21 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 843a4d451fc..d576c36356b 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 7.1.0 + 7.2.0 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index ff94ea238a5..752f5a883ef 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index e4667786798..76f7eefeb60 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 7.1.0 + 7.2.0 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 2e532270d06..5a6c43d77c3 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index df48d20cc04..c3d5e6ceec6 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 7.1.0 + 7.2.0 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index d51161d48c2..1efd3513e82 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 3e386ff0784..cccd49d9046 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 7.1.0 + 7.2.0 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index bddb30514b1..3363674fa38 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 86af7944595..cf39316d865 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 7.1.0 + 7.2.0 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 36249354679..0b9b9b1639f 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 25819c44f65..379e7a20b56 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 7.1.0 + 7.2.0 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 6e96e2f25fa..61926489cbf 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,24 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge pull request `#1484 `_ from tier4/RJD-736/autoware_msgs_support_and_localization_sim_mode_support + Rjd 736/autoware msgs support and localization sim mode support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Add launch argument `simulate_localization` to `scenario_test_runner` +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 1ab93e383ff..eabfb92b2e2 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 7.1.0 + 7.2.0 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index f306ba75dff..74a5e915192 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 7a2bb0820a2..d085b6043c6 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 7.1.0 + 7.2.0 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index ed7cebbb41f..c0362563dad 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,24 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge pull request `#1484 `_ from tier4/RJD-736/autoware_msgs_support_and_localization_sim_mode_support + Rjd 736/autoware msgs support and localization sim mode support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Add launch argument `simulate_localization` to `scenario_test_runner` +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 98e152d4b78..7a505c915ff 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 7.1.0 + 7.2.0 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index bf7f1b1871c..6bee56ba464 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 4cd1e20519e..69b4b354ff6 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 7.1.0 + 7.2.0 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 74287ab308c..007d0a483de 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge remote-tracking branch 'origin/master' into feature/time-to-collision-condition diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 6bf18a22f48..c8308bbce73 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 7.1.0 + 7.2.0 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index ce6500b2e13..a92463cda5e 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,25 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.2.0 (2024-12-16) +------------------ +* Merge pull request `#1484 `_ from tier4/RJD-736/autoware_msgs_support_and_localization_sim_mode_support + Rjd 736/autoware msgs support and localization sim mode support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Merge remote-tracking branch 'origin/RJD-736/autoware_msgs_support' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support +* Add launch argument `simulate_localization` to `scenario_test_runner` +* Contributors: Tatsuya Yamasaki, yamacir-kit + 7.1.0 (2024-12-16) ------------------ * Merge pull request `#1258 `_ from tier4/feature/time-to-collision-condition diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 5edd5d15bc3..1c72387b39a 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 7.1.0 + 7.2.0 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From ada25b16d079d8e4fccc79c21333a9f697ccd73a Mon Sep 17 00:00:00 2001 From: Release Bot Date: Mon, 16 Dec 2024 09:18:55 +0000 Subject: [PATCH 54/54] Bump version of scenario_simulator_v2 from version 7.2.0 to version 7.3.0 --- common/math/arithmetic/CHANGELOG.rst | 9 ++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 20 ++++++++++++++++ common/math/geometry/package.xml | 2 +- .../CHANGELOG.rst | 9 ++++++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 9 ++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 9 ++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 9 ++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 9 ++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 9 ++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 9 ++++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 9 ++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 9 ++++++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 9 ++++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 9 ++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 9 ++++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 9 ++++++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 9 ++++++++ .../package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 9 ++++++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 9 ++++++++ .../openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 9 ++++++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 9 ++++++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 9 ++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 19 +++++++++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 9 ++++++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 23 +++++++++++++++++++ .../simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 11 +++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 20 ++++++++++++++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 9 ++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 9 ++++++++ test_runner/random_test_runner/package.xml | 2 +- .../scenario_test_runner/CHANGELOG.rst | 9 ++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 338 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 00157438e0a..c7b6a88b70f 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index eb64a9ff504..f537c68e4ff 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 7.2.0 + 7.3.0 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index ada9a6569bf..66ce967d505 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,26 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge pull request `#1481 `_ from tier4/feature/multi-level-lanelet-support + Feature/multi level lanelet support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* ref(traffic_simulator, simple_sensor_simulator): refactor altitude checks +* Refactor code to improve readability based on SonarQube findings +* Merge branch 'master' into feature/multi-level-lanelet-support +* Remove comment +* Merge branch 'master' into feature/multi-level-lanelet-support +* Fix missing newline at end of file +* [RJD-1369] Improve Collision Solving for Multi-Level Support + - Enhanced BehaviorTree to consider altitude when detecting potential obstacles, + allowing to ignore objects located at different altitudes. + - Modified the detection sensor by introducing Ego plane determination to exclude objects below the Ego plane, + preventing unnecessary slowing or stopping caused by incorrect detections. +* Contributors: Dawid Moszynski, Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 4e6a717ea81..8a7bc2b4d2c 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 7.2.0 + 7.3.0 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 887c77f337e..bafb69b3ca4 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 53da81744bd..3559db66e79 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 7.2.0 + 7.3.0 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 886ac0d4264..d6f1cd208f2 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 022f47d3339..7befc153190 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 7.2.0 + 7.3.0 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index d35ce5574fd..13c51cc56d2 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 5fc64409eef..4ce85918d8d 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 7.2.0 + 7.3.0 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 4cd7cc43996..cc180c689ca 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge pull request `#1484 `_ from tier4/RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 6308636521d..248f73c126d 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 7.2.0 + 7.3.0 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 173ae3e0eb5..e605b06641b 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,15 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index cf8c7245b1a..3defb0ef4dc 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 7.2.0 + 7.3.0 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 1663efd54b0..4448ce20d6b 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 66c98fb29bd..afd821ef354 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 7.2.0 + 7.3.0 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index b9ea513a641..88832ce9abb 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,15 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 35b7d07eaf6..4996688461e 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 7.2.0 + 7.3.0 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index d7691f345b9..061df30c948 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 640155968db..958c0bc5792 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 7.2.0 + 7.3.0 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index ef2dfbdd120..fd15942339e 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index a834e1e4b59..573580351d8 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 7.2.0 + 7.3.0 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index bc48149ebdb..38ebf1dc490 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,15 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 5f555daba8b..ff4f7516cc7 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 7.2.0 + 7.3.0 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index ed1774681db..dbaacb10980 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index b5ac17c1c0b..eed406acb5e 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 7.2.0 + 7.3.0 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 581c13a2606..4265a0ec76d 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index c2a5042dd7c..1d94189bad1 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 7.2.0 + 7.3.0 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index e69a8044f83..66a59a00197 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index ab58136c7f3..02e6c684ff9 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 7.2.0 + 7.3.0 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 4c0231e37d7..1fa9123d832 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 21b1247bd37..abb4ba5485e 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 7.2.0 + 7.3.0 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 317b0449bc7..744077acb99 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,15 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 88fd01322dc..7d91f787b4d 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 7.2.0 + 7.3.0 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index dfcbe41993a..4317f732786 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,15 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index d576c36356b..8158dc4f1cd 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 7.2.0 + 7.3.0 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 752f5a883ef..42ff8651cd7 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 76f7eefeb60..f514929c106 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 7.2.0 + 7.3.0 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 5a6c43d77c3..b0a3243475b 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index c3d5e6ceec6..46c36eb6741 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 7.2.0 + 7.3.0 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 1efd3513e82..6a1ad058aac 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index cccd49d9046..5048da71c6e 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 7.2.0 + 7.3.0 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 3363674fa38..0a8d758a5bb 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,25 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge pull request `#1481 `_ from tier4/feature/multi-level-lanelet-support + Feature/multi level lanelet support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'feature/multi-level-lanelet-support' of https://github.com/tier4/scenario_simulator_v2 into feature/multi-level-lanelet-support +* ref(traffic_simulator, simple_sensor_simulator): refactor altitude checks +* Refactor code to improve readability based on SonarQube findings +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* [RJD-1369] Improve Collision Solving for Multi-Level Support + - Enhanced BehaviorTree to consider altitude when detecting potential obstacles, + allowing to ignore objects located at different altitudes. + - Modified the detection sensor by introducing Ego plane determination to exclude objects below the Ego plane, + preventing unnecessary slowing or stopping caused by incorrect detections. +* Contributors: Dawid Moszynski, Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index cf39316d865..5ca8a0bda17 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 7.2.0 + 7.3.0 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 0b9b9b1639f..d2c96703654 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 379e7a20b56..76c4550ce48 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 7.2.0 + 7.3.0 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 61926489cbf..c3130844d7f 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,29 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge pull request `#1481 `_ from tier4/feature/multi-level-lanelet-support + Feature/multi level lanelet support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* fix(simple_sensor_simulator): Fix if condition by adding negation to ensure proper logic +* Remove unused function and update comment +* fix(simple_senor_simulator): fix after Szymon discussion +* fix(simple_sensor_simulator): fix after detection_sensor refactor +* ref(traffic_simulator, simple_sensor_simulator): refactor altitude checks +* Refactor code to improve readability based on SonarQube findings +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Removed unrecognized words because spell-check flagged them as invalid +* [RJD-1369] Improve Collision Solving for Multi-Level Support + - Enhanced BehaviorTree to consider altitude when detecting potential obstacles, + allowing to ignore objects located at different altitudes. + - Modified the detection sensor by introducing Ego plane determination to exclude objects below the Ego plane, + preventing unnecessary slowing or stopping caused by incorrect detections. +* Contributors: Dawid Moszynski, Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge pull request `#1484 `_ from tier4/RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index eabfb92b2e2..55060b3d3b9 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 7.2.0 + 7.3.0 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 74a5e915192..12177cf663a 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,17 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* fix(traffic_simulator): revert clang changes +* ref(traffic_simulator, simple_sensor_simulator): refactor altitude checks +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Dawid Moszynski, Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index d085b6043c6..929c22f9a7f 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 7.2.0 + 7.3.0 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index c0362563dad..b6a05f7c227 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,26 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge pull request `#1481 `_ from tier4/feature/multi-level-lanelet-support + Feature/multi level lanelet support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* fix(traffic_simulator): revert clang changes +* ref(traffic_simulator, simple_sensor_simulator): refactor altitude checks +* Merge branch 'master' into feature/multi-level-lanelet-support +* [RJD-1370] Fix 3D Lanelet Matching Issue in cpp_mock_scenario + - Updated the makeRandomPose method to correctly support 3D lanelet matching. +* Fix an issue with unit tests - distanceTest +* Merge branch 'master' into feature/multi-level-lanelet-support +* Removed unrecognized words because spell-check flagged them as invalid +* [RJD-1369] Improve lanelet matching - 3D support + - Enhanced lanelet matching algorithm (`toLaneletPose` method) by incorporating lanelet altitude. + - Defined the `altitude_threshold` parameter that sets the maximum altitude difference to determine when an entity can be matched with a specific lanelet. +* Contributors: Dawid Moszynski, Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge pull request `#1484 `_ from tier4/RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 7a505c915ff..9578bdb927f 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 7.2.0 + 7.3.0 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 6bee56ba464..e9c52213db8 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 69b4b354ff6..b23095deb00 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 7.2.0 + 7.3.0 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 007d0a483de..6289a66c67a 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge branch 'master' into RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index c8308bbce73..0c5024660a6 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 7.2.0 + 7.3.0 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index a92463cda5e..f0ca93e1ae8 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,15 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +7.3.0 (2024-12-16) +------------------ +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Merge branch 'master' into feature/multi-level-lanelet-support +* Contributors: Kotaro Yoshimoto, SzymonParapura + 7.2.0 (2024-12-16) ------------------ * Merge pull request `#1484 `_ from tier4/RJD-736/autoware_msgs_support_and_localization_sim_mode_support diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 1c72387b39a..bcb0fd35f27 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 7.2.0 + 7.3.0 scenario test runner package Tatsuya Yamasaki Apache License 2.0