From 4d7296bf31ce58b41d90c8808f1b0b5dfbeb3f5d Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 20 Oct 2022 11:19:58 +0900 Subject: [PATCH 001/120] Replace msg names to new ones --- test_runner/scenario_test_runner/package.xml | 1 + .../scenario_test_runner.py | 20 +++++++++---------- 2 files changed, 11 insertions(+), 10 deletions(-) diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 0eae28e811c..5b0b561065f 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -15,6 +15,7 @@ simple_sensor_simulator openscenario_interpreter openscenario_preprocessor + openscenario_preprocessor_msgs openscenario_utility diff --git a/test_runner/scenario_test_runner/scenario_test_runner/scenario_test_runner.py b/test_runner/scenario_test_runner/scenario_test_runner/scenario_test_runner.py index 6e4efd11310..d28a47ca84a 100644 --- a/test_runner/scenario_test_runner/scenario_test_runner/scenario_test_runner.py +++ b/test_runner/scenario_test_runner/scenario_test_runner/scenario_test_runner.py @@ -26,10 +26,10 @@ import os import rclpy -from openscenario_interpreter_msgs.srv import ( - PreprocessorCheckDerivativeRemained, - PreprocessorDerive, - PreprocessorLoad +from openscenario_preprocessor_msgs.srv import ( + CheckDerivativeRemained, + Derive, + Load ) from openscenario_utility.conversion import convert from scenario_test_runner.lifecycle_controller import LifecycleController @@ -116,17 +116,17 @@ def __init__( self.current_workflow = None - self.check_preprocessor_client = self.create_client(PreprocessorCheckDerivativeRemained, + self.check_preprocessor_client = self.create_client(CheckDerivativeRemained, '/simulation/openscenario_preprocessor/check') while not self.check_preprocessor_client.wait_for_service(timeout_sec=1.0): self.get_logger().warn('/simulation/openscenario_preprocessor/check service not available, waiting again...') - self.derive_preprocessor_client = self.create_client(PreprocessorDerive, + self.derive_preprocessor_client = self.create_client(Derive, '/simulation/openscenario_preprocessor/derive') while not self.derive_preprocessor_client.wait_for_service(timeout_sec=1.0): self.get_logger().warn('/simulation/openscenario_preprocessor/derive service not available, waiting again...') - self.load_preprocessor_client = self.create_client(PreprocessorLoad, + self.load_preprocessor_client = self.create_client(Load, '/simulation/openscenario_preprocessor/load') while not self.load_preprocessor_client.wait_for_service(timeout_sec=1.0): self.get_logger().warn('/simulation/openscenario_preprocessor/load service not available, waiting again...') @@ -186,7 +186,7 @@ def run_scenarios(self, scenarios: List[Scenario]): if self.post_scenario_to_preprocessor(xosc_scenario): preprocessed_scenarios = [] while self.derivative_remained_on_preprocessor(): - future = self.derive_preprocessor_client.call_async(PreprocessorDerive.Request()) + future = self.derive_preprocessor_client.call_async(Derive.Request()) rclpy.spin_until_future_complete(self, future, timeout_sec=1.0) if future.result() is not None: @@ -268,7 +268,7 @@ def run_preprocessed_scenarios(self, scenarios: List[Scenario]): def post_scenario_to_preprocessor(self, scenario: Scenario): - request = PreprocessorLoad.Request() + request = Load.Request() request.path = str(scenario.path.absolute()) request.expect = scenario.expect request.frame_rate = scenario.frame_rate @@ -286,7 +286,7 @@ def post_scenario_to_preprocessor(self, scenario: Scenario): def derivative_remained_on_preprocessor(self): - future = self.check_preprocessor_client.call_async(PreprocessorCheckDerivativeRemained.Request()) + future = self.check_preprocessor_client.call_async(CheckDerivativeRemained.Request()) rclpy.spin_until_future_complete(self, future, timeout_sec=1.0) if future.result() is not None: self.print_debug('Result of /simulation/openscenario_preprocessor/check: ' From 51064fab9163fb267d6c9f3bf14589e3e3002823 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 8 Nov 2022 11:28:05 +0900 Subject: [PATCH 002/120] Revert "Delete distribution evaluation implementation" This reverts commit 3ae9239c8a0fd3cff725bbf5ae72fa87cd1f1284. --- .../openscenario_interpreter/syntax/distribution_range.hpp | 3 +++ .../openscenario_interpreter/syntax/distribution_set.hpp | 3 +++ .../include/openscenario_interpreter/syntax/histogram.hpp | 2 ++ .../openscenario_interpreter/syntax/parameter_value_set.hpp | 3 +++ .../include/openscenario_interpreter/syntax/range.hpp | 6 +++++- .../syntax/user_defined_distribution.hpp | 2 +- .../syntax/value_set_distribution.hpp | 1 + .../openscenario_interpreter/src/syntax/histogram.cpp | 2 ++ openscenario/openscenario_interpreter/src/syntax/range.cpp | 1 + 9 files changed, 21 insertions(+), 2 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index 924eb626f18..d5982ab7b5d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -37,6 +37,9 @@ struct DistributionRange : private Scope, public ComplexType const Range range; explicit DistributionRange(const pugi::xml_node &, Scope &); + + // TODO: implement evaluate() + auto evaluate() -> Object { throw common::Error(__func__, "is not implemented yet"); } }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index 9244765ef98..b3839ab4e30 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -35,6 +35,9 @@ struct DistributionSet : private Scope, public ComplexType const std::list elements; explicit DistributionSet(const pugi::xml_node &, Scope & scope); + + // TODO: implement evaluate() + auto evaluate() -> Object { throw common::Error(__func__, "is not implemented yet"); } }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index 59968527b39..b8f6879ab25 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -58,6 +58,8 @@ struct Histogram : public ComplexType distribution; explicit Histogram(const pugi::xml_node &, Scope & scope); + + auto evaluate() -> Object; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp index 7af50afc59d..ad652d88493 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp @@ -35,6 +35,9 @@ struct ParameterValueSet : private Scope, public ComplexType const std::list parameter_assignments; explicit ParameterValueSet(const pugi::xml_node &, Scope & scope); + + // TODO: implement evaluate() + auto evaluate() -> Object { throw common::Error(__func__, "is not implemented yet"); } }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/range.hpp index c0bda56a5fd..242931bb5d2 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/range.hpp @@ -34,12 +34,16 @@ inline namespace syntax struct Range { const Double lower_limit = Double::infinity(); - const Double upper_limit = -Double::infinity(); Range() = default; explicit Range(const pugi::xml_node &, Scope &); + + [[nodiscard]] auto evaluate(const Double::value_type value) const -> Double::value_type + { + return std::clamp(value, lower_limit.data, upper_limit.data); + } }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp index f0709a507d0..408413ee7a2 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp @@ -40,8 +40,8 @@ struct UserDefinedDistribution : private Scope, public ComplexType const String content; explicit UserDefinedDistribution(const pugi::xml_node &, const Scope &); - // TODO: implement evaluate()?` + auto evaluate() -> Object { throw common::Error(__func__, "is not implemented yet"); } }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp index 5ab9d33b051..0c70e2a365c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp @@ -38,6 +38,7 @@ struct ValueSetDistribution : public Scope, public ComplexType explicit ValueSetDistribution(const pugi::xml_node &, Scope & scope); // TODO: implement evaluate() + auto evaluate() -> Object { throw common::Error(__func__, "is not implemented yet"); } }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp index d491426c7c2..1aae3f773a1 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp @@ -27,5 +27,7 @@ Histogram::Histogram(const pugi::xml_node & node, openscenario_interpreter::Scop bin_adaptor.intervals.end(), bin_adaptor.densities.begin()) { } + +[[nodiscard]] auto Histogram::evaluate() -> Object { return make(distribution.generate()); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/range.cpp b/openscenario/openscenario_interpreter/src/syntax/range.cpp index ec864ed11e5..17a249647de 100644 --- a/openscenario/openscenario_interpreter/src/syntax/range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/range.cpp @@ -24,5 +24,6 @@ Range::Range(const pugi::xml_node & node, Scope & scope) upper_limit(readAttribute("upperLimit", node, scope)) { } + } // namespace syntax } // namespace openscenario_interpreter From 2c832566d9d4b662898515d321ebf0cd0ee0e703 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 8 Nov 2022 11:28:27 +0900 Subject: [PATCH 003/120] Revert "Delete distribution evaluation implementation" This reverts commit 278177ddfa82888c8ea72efca1e7527169980298. --- .../openscenario_interpreter/syntax/normal_distribution.hpp | 2 ++ .../syntax/poisson_distribution.hpp | 2 ++ .../syntax/probability_distribution_set.hpp | 1 + .../syntax/uniform_distribution.hpp | 1 + .../src/syntax/distribution_definition.cpp | 4 ++-- .../openscenario_interpreter/src/syntax/histogram.cpp | 1 - .../src/syntax/normal_distribution.cpp | 4 ++++ .../src/syntax/poisson_distribution.cpp | 4 ++++ .../src/syntax/probability_distribution_set.cpp | 4 ++++ .../src/syntax/uniform_distribution.cpp | 6 ++++++ 10 files changed, 26 insertions(+), 3 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp index cd24b26a5e5..5824af9a36f 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp @@ -49,6 +49,8 @@ struct NormalDistribution : public ComplexType StochasticDistributionClass> distribution; explicit NormalDistribution(const pugi::xml_node &, Scope & scope); + + auto evaluate() -> Object; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index 6603a21cef9..4687e391728 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -43,6 +43,8 @@ struct PoissonDistribution : public ComplexType StochasticDistributionClass> distribution; explicit PoissonDistribution(const pugi::xml_node &, Scope & scope); + + auto evaluate() -> Object; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index f15072816a1..292e7e60dce 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -54,6 +54,7 @@ struct ProbabilityDistributionSet : public ComplexType explicit ProbabilityDistributionSet(const pugi::xml_node &, Scope & scope); + auto evaluate() -> Object; // TODO: implement evaluate() // Use std::discrete_distribution from }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index 12f67d3fef3..e9a0fcc9c65 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -42,6 +42,7 @@ struct UniformDistribution : public ComplexType // TODO: implement evaluate() // Use std::uniform_real_distribution from + auto evaluate() -> Object; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_definition.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_definition.cpp index 7499024a894..705adb01a8a 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_definition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_definition.cpp @@ -23,8 +23,8 @@ DistributionDefinition::DistributionDefinition(const pugi::xml_node & tree, Scop // clang-format off : Group( choice(tree, - std::make_pair("Deterministic", [&](auto && node){return make(node,scope);}), - std::make_pair("Stochastic", [&](auto && node){return make(node,scope);}))) + std::make_pair("Deterministic", [&](auto && node){return make(node,scope);}), + std::make_pair("Stochastic", [&](auto && node){return make(node,scope);}))) // clang-format on { } diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp index 1aae3f773a1..c73a044d775 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp @@ -27,7 +27,6 @@ Histogram::Histogram(const pugi::xml_node & node, openscenario_interpreter::Scop bin_adaptor.intervals.end(), bin_adaptor.densities.begin()) { } - [[nodiscard]] auto Histogram::evaluate() -> Object { return make(distribution.generate()); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp index bcc47d2d840..ba3d3c2f917 100644 --- a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp @@ -29,5 +29,9 @@ NormalDistribution::NormalDistribution( static_cast(variance.data)) { } +[[nodiscard]] auto NormalDistribution::evaluate() -> Object +{ + return make(range.evaluate(distribution.generate())); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp index 3cf4cf1bb64..7d081c7f059 100644 --- a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp @@ -26,5 +26,9 @@ PoissonDistribution::PoissonDistribution( distribution(scope.ref(std::string("randomSeed")).data, expected_value.data) { } +[[nodiscard]] auto PoissonDistribution::evaluate() -> Object +{ + return make(range.evaluate(distribution.generate())); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp index b5ba955a218..99e36eb1c0d 100644 --- a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp @@ -28,5 +28,9 @@ ProbabilityDistributionSet::ProbabilityDistributionSet( adaptor.probabilities.end()) { } +[[nodiscard]] auto ProbabilityDistributionSet::evaluate() -> Object +{ + return make(adaptor.values.at(distribution.generate())); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index bc48d78f0c8..dc1b4d46b51 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -27,5 +27,11 @@ UniformDistribution::UniformDistribution( range.upper_limit.data) { } +[[nodiscard]] auto UniformDistribution::evaluate() -> Object +{ + // Return a value without filtering by this->range here + // because it is embedded in distribution + return make(distribution.generate()); +} } // namespace syntax } // namespace openscenario_interpreter From fde2aa3a83818fde0074134506c573d61c22fb17 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 8 Nov 2022 13:39:19 +0900 Subject: [PATCH 004/120] doc(interpreter): update comments for stochastic distributions Signed-off-by: Kotaro Yoshimoto --- .../include/openscenario_interpreter/syntax/histogram.hpp | 3 ++- .../syntax/probability_distribution_set.hpp | 2 -- .../openscenario_interpreter/syntax/uniform_distribution.hpp | 2 -- .../syntax/user_defined_distribution.hpp | 3 ++- .../src/syntax/uniform_distribution.cpp | 3 ++- 5 files changed, 6 insertions(+), 7 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index b8f6879ab25..f513e2453cb 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -36,7 +36,8 @@ inline namespace syntax struct Histogram : public ComplexType { /** - * Note: HistogramBin must be stored in continuous range and ascending order, to `bins` + * Note: HistogramBin must be stored in continuous range and ascending order to `bins` + * due to restriction of `BinAdapter` */ const std::list bins; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index 292e7e60dce..bf2b1cf4b53 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -55,8 +55,6 @@ struct ProbabilityDistributionSet : public ComplexType explicit ProbabilityDistributionSet(const pugi::xml_node &, Scope & scope); auto evaluate() -> Object; - // TODO: implement evaluate() - // Use std::discrete_distribution from }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index e9a0fcc9c65..e1c780e30e5 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -40,8 +40,6 @@ struct UniformDistribution : public ComplexType explicit UniformDistribution(const pugi::xml_node &, Scope & scope); - // TODO: implement evaluate() - // Use std::uniform_real_distribution from auto evaluate() -> Object; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp index 408413ee7a2..e7bc2234321 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp @@ -40,7 +40,8 @@ struct UserDefinedDistribution : private Scope, public ComplexType const String content; explicit UserDefinedDistribution(const pugi::xml_node &, const Scope &); - // TODO: implement evaluate()?` + + // TODO: implement evaluate()` auto evaluate() -> Object { throw common::Error(__func__, "is not implemented yet"); } }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index dc1b4d46b51..0fe41999435 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -27,10 +27,11 @@ UniformDistribution::UniformDistribution( range.upper_limit.data) { } + [[nodiscard]] auto UniformDistribution::evaluate() -> Object { // Return a value without filtering by this->range here - // because it is embedded in distribution + // because it is embedded in StochasticDistributionClass return make(distribution.generate()); } } // namespace syntax From ff0bbfb9b26000b9c63ea96c9feb3fb32b68ba55 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 8 Nov 2022 14:07:28 +0900 Subject: [PATCH 005/120] chore(compile error): fix compile error Signed-off-by: Kotaro Yoshimoto --- .../openscenario_interpreter/syntax/distribution_range.hpp | 3 +-- .../openscenario_interpreter/syntax/distribution_set.hpp | 3 +-- .../openscenario_interpreter/syntax/parameter_value_set.hpp | 2 +- .../syntax/user_defined_distribution.hpp | 3 +-- .../syntax/value_set_distribution.hpp | 3 +-- .../src/syntax/distribution_range.cpp | 5 +++++ .../openscenario_interpreter/src/syntax/distribution_set.cpp | 5 +++++ .../src/syntax/parameter_value_set.cpp | 5 +++++ .../src/syntax/user_defined_distribution.cpp | 5 +++++ .../src/syntax/value_set_distribution.cpp | 5 +++++ 10 files changed, 30 insertions(+), 9 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index d5982ab7b5d..412a5b561c4 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -38,8 +38,7 @@ struct DistributionRange : private Scope, public ComplexType explicit DistributionRange(const pugi::xml_node &, Scope &); - // TODO: implement evaluate() - auto evaluate() -> Object { throw common::Error(__func__, "is not implemented yet"); } + auto evaluate() -> Object; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index b3839ab4e30..6542641bc28 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -36,8 +36,7 @@ struct DistributionSet : private Scope, public ComplexType explicit DistributionSet(const pugi::xml_node &, Scope & scope); - // TODO: implement evaluate() - auto evaluate() -> Object { throw common::Error(__func__, "is not implemented yet"); } + auto evaluate() -> Object; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp index ad652d88493..c28d2081f28 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp @@ -37,7 +37,7 @@ struct ParameterValueSet : private Scope, public ComplexType explicit ParameterValueSet(const pugi::xml_node &, Scope & scope); // TODO: implement evaluate() - auto evaluate() -> Object { throw common::Error(__func__, "is not implemented yet"); } + auto evaluate() -> Object; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp index e7bc2234321..ad3894ea8df 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp @@ -41,8 +41,7 @@ struct UserDefinedDistribution : private Scope, public ComplexType explicit UserDefinedDistribution(const pugi::xml_node &, const Scope &); - // TODO: implement evaluate()` - auto evaluate() -> Object { throw common::Error(__func__, "is not implemented yet"); } + auto evaluate() -> Object; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp index 0c70e2a365c..577e727d7c0 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp @@ -37,8 +37,7 @@ struct ValueSetDistribution : public Scope, public ComplexType explicit ValueSetDistribution(const pugi::xml_node &, Scope & scope); - // TODO: implement evaluate() - auto evaluate() -> Object { throw common::Error(__func__, "is not implemented yet"); } + auto evaluate() -> Object; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp index f90a7697f96..d9260cff53d 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp @@ -24,5 +24,10 @@ DistributionRange::DistributionRange(const pugi::xml_node & node, Scope & scope) { } +auto DistributionRange::evaluate() -> Object +{ + throw common::Error("DistributionRange is not implemented yet"); +} + } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp index eb2b62b07a0..eb67f0c7fdb 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp @@ -23,5 +23,10 @@ DistributionSet::DistributionSet(const pugi::xml_node & node, Scope & scope) : Scope(scope), elements(readElements("Element", node, local())) { } + +auto DistributionSet::evaluate() -> Object +{ + throw common::Error("DistributionSet is not implemented yet"); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp b/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp index 0c727b73516..6563a635cd8 100644 --- a/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp @@ -25,5 +25,10 @@ ParameterValueSet::ParameterValueSet( parameter_assignments(readElements("ParameterAssignment", node, local())) { } + +auto ParameterValueSet::evaluate() -> Object +{ + throw common::Error("ParameterValueSet is not implemented yet"); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/user_defined_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/user_defined_distribution.cpp index d8f08237f29..6b6d4ff7290 100644 --- a/openscenario/openscenario_interpreter/src/syntax/user_defined_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/user_defined_distribution.cpp @@ -26,5 +26,10 @@ UserDefinedDistribution::UserDefinedDistribution(const pugi::xml_node & node, co content(readContent(node, local())) { } + +auto UserDefinedDistribution::evaluate() -> Object +{ + throw common::Error("UserDefinedDistribution is not implemented yet"); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp index c171ba2a4cb..97035fa76f0 100644 --- a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp @@ -25,5 +25,10 @@ ValueSetDistribution::ValueSetDistribution( parameter_value_sets(readElements("ParameterValueSet", node, scope)) { } + +auto ValueSetDistribution::evaluate() -> Object +{ + throw common::Error("ValueSetDistribution is not implemented yet"); +} } // namespace syntax } // namespace openscenario_interpreter From d4f4a02f0dbf8ba81f3ec8758e5c5e0e6fe350f3 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 10 Nov 2022 14:54:13 +0900 Subject: [PATCH 006/120] feat(interpreter): implement DistributionSet::evaluate Signed-off-by: Kotaro Yoshimoto --- .../openscenario_interpreter/syntax/distribution_set.hpp | 4 ++-- .../openscenario_interpreter/utility/distribution.hpp | 8 ++++++++ .../src/syntax/distribution_set.cpp | 9 +++++++-- 3 files changed, 17 insertions(+), 4 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index 6542641bc28..f9fec822186 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -16,7 +16,7 @@ #define OPENSCENARIO_INTERPRETER__DISTRIBUTION_SET_HPP_ #include - +#include namespace openscenario_interpreter { inline namespace syntax @@ -36,7 +36,7 @@ struct DistributionSet : private Scope, public ComplexType explicit DistributionSet(const pugi::xml_node &, Scope & scope); - auto evaluate() -> Object; + auto evaluate() -> SingleParameterList; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/utility/distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/utility/distribution.hpp index 6ccf88a5fd5..cf54c43502a 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/utility/distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/utility/distribution.hpp @@ -39,6 +39,14 @@ struct StochasticDistributionClass auto generate() { return distribution(random_engine); } }; + +struct SingleParameterList : public std::vector {}; +//using UnnamedParameterSet = std::vector; +//using UnnamedParameterList = std::vector; + +//using ParameterSet = std::unordered_map; +//using ParameterList = std::vector; + } // namespace utility } // namespace openscenario_interpreter #endif // OPENSCENARIO_INTERPRETER__DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp index eb67f0c7fdb..468240884d1 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp @@ -24,9 +24,14 @@ DistributionSet::DistributionSet(const pugi::xml_node & node, Scope & scope) { } -auto DistributionSet::evaluate() -> Object +auto DistributionSet::evaluate() -> SingleParameterList { - throw common::Error("DistributionSet is not implemented yet"); + SingleParameterList list; + for (const auto & element : elements) { + list.emplace_back(make(element.value)); + } + return list; } + } // namespace syntax } // namespace openscenario_interpreter From 0f88fc25d4c3e7bd5d2464c7dbdbdbeed06dad00 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 10 Nov 2022 15:02:04 +0900 Subject: [PATCH 007/120] fix(interpreter): add missing attribute in DistributionRange Signed-off-by: Kotaro Yoshimoto --- .../openscenario_interpreter/syntax/distribution_range.hpp | 2 ++ .../src/syntax/distribution_range.cpp | 4 +++- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index 412a5b561c4..23d304cba7b 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -34,6 +34,8 @@ inline namespace syntax * -------------------------------------------------------------------------- */ struct DistributionRange : private Scope, public ComplexType { + const Double step_width; + const Range range; explicit DistributionRange(const pugi::xml_node &, Scope &); diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp index d9260cff53d..80c936bd12d 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp @@ -20,7 +20,9 @@ namespace openscenario_interpreter inline namespace syntax { DistributionRange::DistributionRange(const pugi::xml_node & node, Scope & scope) -: Scope(scope), range(readElement("Range", node, local())) +: Scope(scope), + step_width(readAttribute("stepWidth", node, local())), + range(readElement("Range", node, local())) { } From 70ac4dc550559b029ea7e55a70ea5bd59826a338 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 10 Nov 2022 15:07:23 +0900 Subject: [PATCH 008/120] feat(interpreter): implement DistributionRange::evaluate Signed-off-by: Kotaro Yoshimoto --- .../syntax/distribution_range.hpp | 3 ++- .../src/syntax/distribution_range.cpp | 9 +++++++-- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index 23d304cba7b..b836e3ccf1d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -17,6 +17,7 @@ #include #include +#include #include namespace openscenario_interpreter @@ -40,7 +41,7 @@ struct DistributionRange : private Scope, public ComplexType explicit DistributionRange(const pugi::xml_node &, Scope &); - auto evaluate() -> Object; + auto evaluate() -> SingleParameterList; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp index 80c936bd12d..59ec3551362 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp @@ -26,9 +26,14 @@ DistributionRange::DistributionRange(const pugi::xml_node & node, Scope & scope) { } -auto DistributionRange::evaluate() -> Object +auto DistributionRange::evaluate() -> SingleParameterList { - throw common::Error("DistributionRange is not implemented yet"); + SingleParameterList list; + for (double parameter = range.lower_limit; parameter <= range.upper_limit; + parameter += step_width) { + list.emplace_back(make(parameter)); + } + return list; } } // namespace syntax From 4cacaa43d3d7c3a3e69903dc5fc30187593d20f2 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 7 Dec 2022 10:33:23 +0900 Subject: [PATCH 009/120] chore(interpreter): fix include guard Signed-off-by: Kotaro Yoshimoto --- .../include/scenario_simulator_exception/concatenate.hpp | 2 +- .../include/scenario_simulator_exception/fold.hpp | 2 +- 2 files changed, 2 insertions(+), 2 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..02a4c57b120 100644 --- a/common/scenario_simulator_exception/include/scenario_simulator_exception/concatenate.hpp +++ b/common/scenario_simulator_exception/include/scenario_simulator_exception/concatenate.hpp @@ -36,4 +36,4 @@ inline auto concatenate = [](auto &&... xs) { } // namespace scenario_simulator_exception } // namespace common -#endif // OPENSCENARIO_INTERPRETER__CONCATENATE_HPP_ +#endif // SCENARIO_SIMULATOR_EXCEPTION__CONCATENATE_HPP_ diff --git a/common/scenario_simulator_exception/include/scenario_simulator_exception/fold.hpp b/common/scenario_simulator_exception/include/scenario_simulator_exception/fold.hpp index 13ec28b8bc2..2f2ae4ba034 100644 --- a/common/scenario_simulator_exception/include/scenario_simulator_exception/fold.hpp +++ b/common/scenario_simulator_exception/include/scenario_simulator_exception/fold.hpp @@ -52,4 +52,4 @@ constexpr decltype(auto) fold_right(F && f, T && x, Ts &&... xs) } // namespace scenario_simulator_exception } // namespace common -#endif // OPENSCENARIO_INTERPRETER__FOLD_HPP_ +#endif // SCENARIO_SIMULATOR_EXCEPTION__FOLD_HPP_ From edfebf7b3a4c673754b89c6f1e11ba7153b0ede4 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 7 Dec 2022 10:42:02 +0900 Subject: [PATCH 010/120] chore(interpreter): fix include path Signed-off-by: Kotaro Yoshimoto --- .../openscenario_interpreter/syntax/distribution_range.hpp | 2 +- .../openscenario_interpreter/syntax/distribution_set.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index b836e3ccf1d..f953aa0a81d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -17,7 +17,7 @@ #include #include -#include +#include #include namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index f9fec822186..eb5bc911178 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -16,7 +16,7 @@ #define OPENSCENARIO_INTERPRETER__DISTRIBUTION_SET_HPP_ #include -#include +#include namespace openscenario_interpreter { inline namespace syntax From 1f69890f8e5424da3d8d2a89c7e950deac276168 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 7 Dec 2022 10:43:07 +0900 Subject: [PATCH 011/120] feat(interpreter): add SingleParameterList struct Signed-off-by: Kotaro Yoshimoto --- .../random/stochastic_distribution_sampler.hpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/random/stochastic_distribution_sampler.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/random/stochastic_distribution_sampler.hpp index b9c41f38efd..ffa7ff4dd8c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/random/stochastic_distribution_sampler.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/random/stochastic_distribution_sampler.hpp @@ -36,6 +36,14 @@ struct StochasticDistributionSampler auto operator()(std::mt19937 & random_engine) { return distribute(random_engine); } }; + +struct SingleParameterList : public std::vector {}; +//using UnnamedParameterSet = std::vector; +//using UnnamedParameterList = std::vector; + +//using ParameterSet = std::unordered_map; +//using ParameterList = std::vector; + } // namespace random } // namespace openscenario_interpreter #endif // OPENSCENARIO_INTERPRETER__STOCHASTIC_DISTRIBUTION_SAMPLER_HPP_ From 3900b81597a33125c723852959a1db7a74852f83 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 23 Dec 2022 14:59:27 +0900 Subject: [PATCH 012/120] refactor(interpreter): update interface Signed-off-by: Kotaro Yoshimoto --- .../random/stochastic_distribution_sampler.hpp | 0 .../syntax/distribution_range.hpp | 3 +-- .../syntax/distribution_set.hpp | 3 +-- .../openscenario_interpreter/syntax/histogram.hpp | 5 +++-- .../syntax/normal_distribution.hpp | 5 +++-- .../syntax/poisson_distribution.hpp | 5 +++-- .../syntax/probability_distribution_set.hpp | 3 ++- .../openscenario_interpreter/syntax/stochastic.hpp | 12 +++++++++++- .../syntax/stochastic_distribution.hpp | 1 + .../syntax/uniform_distribution.hpp | 2 +- .../src/syntax/distribution_range.cpp | 4 ++-- .../src/syntax/distribution_set.cpp | 4 ++-- .../src/syntax/histogram.cpp | 2 +- .../src/syntax/normal_distribution.cpp | 5 ++++- .../src/syntax/poisson_distribution.cpp | 2 +- .../src/syntax/probability_distribution_set.cpp | 2 +- .../src/syntax/uniform_distribution.cpp | 2 +- 17 files changed, 38 insertions(+), 22 deletions(-) delete mode 100644 openscenario/openscenario_interpreter/include/openscenario_interpreter/random/stochastic_distribution_sampler.hpp diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/random/stochastic_distribution_sampler.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/random/stochastic_distribution_sampler.hpp deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index f953aa0a81d..f6ec75a343e 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -17,7 +17,6 @@ #include #include -#include #include namespace openscenario_interpreter @@ -41,7 +40,7 @@ struct DistributionRange : private Scope, public ComplexType explicit DistributionRange(const pugi::xml_node &, Scope &); - auto evaluate() -> SingleParameterList; + auto derive() -> std::vector; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index eb5bc911178..ff06347411f 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -16,7 +16,6 @@ #define OPENSCENARIO_INTERPRETER__DISTRIBUTION_SET_HPP_ #include -#include namespace openscenario_interpreter { inline namespace syntax @@ -36,7 +35,7 @@ struct DistributionSet : private Scope, public ComplexType explicit DistributionSet(const pugi::xml_node &, Scope & scope); - auto evaluate() -> SingleParameterList; + auto derive() -> std::vector; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index 34d7c70d98f..9191e762c0e 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -15,6 +15,7 @@ #ifndef OPENSCENARIO_INTERPRETER__HISTOGRAM_HPP_ #define OPENSCENARIO_INTERPRETER__HISTOGRAM_HPP_ +#include #include #include #include @@ -33,7 +34,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ -struct Histogram : public ComplexType, private Scope +struct Histogram : public ComplexType, private Scope, public StochasticDistributionBase { /** * Note: HistogramBin must be stored in continuous range and ascending order to `bins` @@ -61,7 +62,7 @@ struct Histogram : public ComplexType, private Scope explicit Histogram(const pugi::xml_node &, Scope & scope); - auto evaluate() -> Object; + auto derive() -> Object override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp index 4ff2ec715f4..c92615f02ae 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp @@ -15,6 +15,7 @@ #ifndef OPENSCENARIO_INTERPRETER__NORMAL_DISTRIBUTION_HPP_ #define OPENSCENARIO_INTERPRETER__NORMAL_DISTRIBUTION_HPP_ +#include #include #include #include @@ -37,7 +38,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ -struct NormalDistribution : public ComplexType, private Scope +struct NormalDistribution : public ComplexType, private Scope, public StochasticDistributionBase { const Range range; @@ -51,7 +52,7 @@ struct NormalDistribution : public ComplexType, private Scope explicit NormalDistribution(const pugi::xml_node &, Scope & scope); - auto evaluate() -> Object; + auto derive() -> Object override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index 1eecd63de1d..1d42f396d41 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -19,6 +19,7 @@ #include #include #include +#include namespace openscenario_interpreter { @@ -34,7 +35,7 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct PoissonDistribution : public ComplexType, private Scope +struct PoissonDistribution : public ComplexType, private Scope, public StochasticDistributionBase { const Range range; @@ -46,7 +47,7 @@ struct PoissonDistribution : public ComplexType, private Scope explicit PoissonDistribution(const pugi::xml_node &, Scope & scope); - auto evaluate() -> Object; + auto derive() -> Object override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index 29e2fb164aa..e0c550a1657 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -15,6 +15,7 @@ #ifndef OPENSCENARIO_INTERPRETER__PROBABILITY_DISTRIBUTION_SET_HPP_ #define OPENSCENARIO_INTERPRETER__PROBABILITY_DISTRIBUTION_SET_HPP_ +#include #include #include @@ -56,7 +57,7 @@ struct ProbabilityDistributionSet : public ComplexType, private Scope explicit ProbabilityDistributionSet(const pugi::xml_node &, Scope & scope); - auto evaluate() -> Object; + auto derive() -> Object override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp index 424556701b5..e8bce20ffef 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp @@ -15,6 +15,7 @@ #ifndef OPENSCENARIO_INTERPRETER__STOCHASTIC_HPP_ #define OPENSCENARIO_INTERPRETER__STOCHASTIC_HPP_ +#include #include #include #include @@ -38,7 +39,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ -struct Stochastic : public ComplexType +struct Stochastic : public ComplexType, public ParameterDistributionBase { const UnsignedInt number_of_test_runs; @@ -47,6 +48,15 @@ struct Stochastic : public ComplexType const StochasticDistribution stochastic_distribution; explicit Stochastic(const pugi::xml_node &, Scope & scope); + + auto derive() -> std::vector> override + { + std::vector> parameters; + for(int i = 0; i < number_of_test_runs; i++){ + parameters.emplace_back({{stochastic_distribution.parameter_name, stochastic_distribution.derive()}}); + } + return stochastic_distribution.derive(); + } }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp index 37eb08e97e5..e2788991dda 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp @@ -18,6 +18,7 @@ #include #include #include +#include namespace openscenario_interpreter { diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index 50c5771697b..d90c99d9c6f 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -42,7 +42,7 @@ struct UniformDistribution : public ComplexType, private Scope explicit UniformDistribution(const pugi::xml_node &, Scope & scope); - auto evaluate() -> Object; + auto derive() -> Object override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp index 59ec3551362..329ae6de6ec 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp @@ -26,9 +26,9 @@ DistributionRange::DistributionRange(const pugi::xml_node & node, Scope & scope) { } -auto DistributionRange::evaluate() -> SingleParameterList +auto DistributionRange::derive() -> std::vector { - SingleParameterList list; + std::vector list; for (double parameter = range.lower_limit; parameter <= range.upper_limit; parameter += step_width) { list.emplace_back(make(parameter)); diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp index 468240884d1..7026ab8b623 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp @@ -24,9 +24,9 @@ DistributionSet::DistributionSet(const pugi::xml_node & node, Scope & scope) { } -auto DistributionSet::evaluate() -> SingleParameterList +auto DistributionSet::derive() -> std::vector { - SingleParameterList list; + std::vector list; for (const auto & element : elements) { list.emplace_back(make(element.value)); } diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp index 5017ff1752c..bff1c66c09f 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp @@ -29,6 +29,6 @@ Histogram::Histogram(const pugi::xml_node & node, openscenario_interpreter::Scop { } -auto Histogram::evaluate() -> Object { return make(distribute(random_engine)); } +auto Histogram::derive() -> Object { return make(distribute(random_engine)); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp index 03ee4cdd54d..7f1252e0b75 100644 --- a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp @@ -30,6 +30,9 @@ NormalDistribution::NormalDistribution( { } -auto NormalDistribution::evaluate() -> Object { return make(distribute(random_engine)); } +auto NormalDistribution::derive() -> Object +{ + return make(distribute(random_engine)); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp index 032bf5a8b31..4ccff80708c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp @@ -29,6 +29,6 @@ PoissonDistribution::PoissonDistribution( { } -auto PoissonDistribution::evaluate() -> Object { return make(distribute(random_engine)); } +auto PoissonDistribution::derive() -> Object { return make(distribute(random_engine)); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp index 94dd9c72619..46c487f1a0d 100644 --- a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp @@ -37,7 +37,7 @@ ProbabilityDistributionSet::ProbabilityDistributionSet( { } -auto ProbabilityDistributionSet::evaluate() -> Object +auto ProbabilityDistributionSet::derive() -> Object { size_t index = distribute(random_engine); return elements.at(index); diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index 8bf6bb49284..da4f68b35c6 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -28,6 +28,6 @@ UniformDistribution::UniformDistribution( { } -auto UniformDistribution::evaluate() -> Object { return make(distribute(random_engine)); } +auto UniformDistribution::derive() -> Object { return make(distribute(random_engine)); } } // namespace syntax } // namespace openscenario_interpreter From a37bd58aca115c9c90717ce937b57aaec73ac1d0 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 23 Dec 2022 15:00:01 +0900 Subject: [PATCH 013/120] refactor(interpreter): update interface Signed-off-by: Kotaro Yoshimoto --- .../openscenario_interpreter/syntax/distribution_set.hpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index ff06347411f..ec9fa9447c7 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -29,6 +29,12 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ +struct SingleParameterList : public std::vector {}; +//using UnnamedParameterSet = std::vector; +//using UnnamedParameterList = std::vector; + +//using ParameterSet = std::unordered_map; +//using ParameterList = std::vector; struct DistributionSet : private Scope, public ComplexType { const std::list elements; From fd23c5c883a39ee25d639b6e013c4b797f05bae6 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 6 Jan 2023 17:01:02 +0900 Subject: [PATCH 014/120] feat(interpreter): add base classes for parameter distributions Signed-off-by: Kotaro Yoshimoto --- .../parameter_distribution.hpp | 33 +++++++++++++++++++ 1 file changed, 33 insertions(+) create mode 100644 openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp new file mode 100644 index 00000000000..0ae14fad507 --- /dev/null +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -0,0 +1,33 @@ +// 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__PARAMETER_DISTRIBUTION_HPP_ +#define OPENSCENARIO_INTERPRETER__PARAMETER_DISTRIBUTION_HPP_ + +#include +#include + +namespace openscenario_interpreter +{ +struct SingleParameterDistributionBase +{ + virtual auto derive() -> std::vector = 0; +}; + +struct MultiParameterDistributionBase +{ + virtual auto derive() -> std::vector> = 0; +}; +} // namespace openscenario_interpreter +#endif //OPENSCENARIO_INTERPRETER__PARAMETER_DISTRIBUTION_HPP_ From 05afff8c91281cd74dd29cf98e72101b647893f2 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 6 Jan 2023 17:02:20 +0900 Subject: [PATCH 015/120] chore(interpreter): delete support for UserDefinedDistribution Signed-off-by: Kotaro Yoshimoto --- .../syntax/stochastic_distribution_type.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp index e7092757ef0..206b15c3d47 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp @@ -54,7 +54,7 @@ DEFINE_LAZY_VISITOR( CASE(UniformDistribution), // CASE(PoissonDistribution), // CASE(Histogram), // - CASE(UserDefinedDistribution), // +// CASE(UserDefinedDistribution), // ); } // namespace syntax } // namespace openscenario_interpreter From e52220c0a88abeee3e75227196c19d702651faeb Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 6 Jan 2023 17:03:45 +0900 Subject: [PATCH 016/120] feat(interpreter): use single parameter distribution interface in stochastic parameter distributions Signed-off-by: Kotaro Yoshimoto --- .../include/openscenario_interpreter/syntax/histogram.hpp | 5 ++--- .../openscenario_interpreter/syntax/normal_distribution.hpp | 4 ++-- .../syntax/poisson_distribution.hpp | 5 ++--- .../syntax/probability_distribution_set.hpp | 6 ++++-- .../syntax/uniform_distribution.hpp | 5 +++-- .../openscenario_interpreter/src/syntax/histogram.cpp | 5 ++++- .../src/syntax/normal_distribution.cpp | 5 ++--- .../src/syntax/poisson_distribution.cpp | 6 ++++-- .../src/syntax/probability_distribution_set.cpp | 5 ++--- .../src/syntax/uniform_distribution.cpp | 6 ++++-- 10 files changed, 29 insertions(+), 23 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index 9191e762c0e..a291cb438e2 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -34,7 +34,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ -struct Histogram : public ComplexType, private Scope, public StochasticDistributionBase +struct Histogram : public ComplexType, private Scope, public SingleParameterDistributionBase { /** * Note: HistogramBin must be stored in continuous range and ascending order to `bins` @@ -61,8 +61,7 @@ struct Histogram : public ComplexType, private Scope, public StochasticDistribut std::mt19937 random_engine; explicit Histogram(const pugi::xml_node &, Scope & scope); - - auto derive() -> Object override; + auto derive() -> std::vector override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp index c92615f02ae..cb479fb8380 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp @@ -38,7 +38,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ -struct NormalDistribution : public ComplexType, private Scope, public StochasticDistributionBase +struct NormalDistribution : public ComplexType, private Scope, public SingleParameterDistributionBase { const Range range; @@ -52,7 +52,7 @@ struct NormalDistribution : public ComplexType, private Scope, public Stochastic explicit NormalDistribution(const pugi::xml_node &, Scope & scope); - auto derive() -> Object override; + auto derive() -> std::vector override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index 1d42f396d41..eede45d8478 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -35,7 +35,7 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct PoissonDistribution : public ComplexType, private Scope, public StochasticDistributionBase +struct PoissonDistribution : public ComplexType, private Scope, public SingleParameterDistributionBase { const Range range; @@ -46,8 +46,7 @@ struct PoissonDistribution : public ComplexType, private Scope, public Stochasti std::mt19937 random_engine; explicit PoissonDistribution(const pugi::xml_node &, Scope & scope); - - auto derive() -> Object override; + auto derive() -> std::vector override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index e0c550a1657..dd81bbc658d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -33,7 +33,9 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ -struct ProbabilityDistributionSet : public ComplexType, private Scope +struct ProbabilityDistributionSet : public ComplexType, + private Scope, + public SingleParameterDistributionBase { const std::vector elements; @@ -57,7 +59,7 @@ struct ProbabilityDistributionSet : public ComplexType, private Scope explicit ProbabilityDistributionSet(const pugi::xml_node &, Scope & scope); - auto derive() -> Object override; + auto derive() -> std::vector override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index d90c99d9c6f..f2152a37ff6 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -15,6 +15,7 @@ #ifndef OPENSCENARIO_INTERPRETER__UNIFORM_DISTRIBUTION_HPP_ #define OPENSCENARIO_INTERPRETER__UNIFORM_DISTRIBUTION_HPP_ +#include #include #include #include @@ -32,7 +33,7 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct UniformDistribution : public ComplexType, private Scope +struct UniformDistribution : public ComplexType, private Scope, public SingleParameterDistributionBase { const Range range; @@ -42,7 +43,7 @@ struct UniformDistribution : public ComplexType, private Scope explicit UniformDistribution(const pugi::xml_node &, Scope & scope); - auto derive() -> Object override; + auto derive() -> std::vector override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp index bff1c66c09f..3c22f148e1b 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp @@ -29,6 +29,9 @@ Histogram::Histogram(const pugi::xml_node & node, openscenario_interpreter::Scop { } -auto Histogram::derive() -> Object { return make(distribute(random_engine)); } +std::vector Histogram::derive() +{ + return std::vector({make(distribute(random_engine))}); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp index 7f1252e0b75..16a6654593c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp @@ -29,10 +29,9 @@ NormalDistribution::NormalDistribution( random_engine(scope.seed) { } - -auto NormalDistribution::derive() -> Object +std::vector NormalDistribution::derive() { - return make(distribute(random_engine)); + return std::vector({make(distribute(random_engine))}); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp index 4ccff80708c..1e2a3628b9b 100644 --- a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp @@ -28,7 +28,9 @@ PoissonDistribution::PoissonDistribution( random_engine(scope.seed) { } - -auto PoissonDistribution::derive() -> Object { return make(distribute(random_engine)); } +std::vector PoissonDistribution::derive() +{ + return std::vector({make(distribute(random_engine))}); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp index 46c487f1a0d..2a08a97a563 100644 --- a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp @@ -36,11 +36,10 @@ ProbabilityDistributionSet::ProbabilityDistributionSet( random_engine(scope.seed) { } - -auto ProbabilityDistributionSet::derive() -> Object +std::vector ProbabilityDistributionSet::derive() { size_t index = distribute(random_engine); - return elements.at(index); + return std::vector({elements.at(index)}); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index da4f68b35c6..0caacc91af5 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -27,7 +27,9 @@ UniformDistribution::UniformDistribution( random_engine(scope.seed) { } - -auto UniformDistribution::derive() -> Object { return make(distribute(random_engine)); } +std::vector UniformDistribution::derive() +{ + return std::vector({make(distribute(random_engine))}); +} } // namespace syntax } // namespace openscenario_interpreter From e06dd23f11d2d338e956f430404f6180df126c27 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 6 Jan 2023 17:04:30 +0900 Subject: [PATCH 017/120] feat(interpreter): implement Stochatic::derive() Signed-off-by: Kotaro Yoshimoto --- .../syntax/stochastic.hpp | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp index e8bce20ffef..09419323578 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp @@ -39,23 +39,27 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ -struct Stochastic : public ComplexType, public ParameterDistributionBase +struct Stochastic : public ComplexType, public SingleParameterDistributionBase { const UnsignedInt number_of_test_runs; const Double random_seed; - const StochasticDistribution stochastic_distribution; + StochasticDistribution stochastic_distribution; explicit Stochastic(const pugi::xml_node &, Scope & scope); - auto derive() -> std::vector> override + auto derive() -> std::vector override { - std::vector> parameters; - for(int i = 0; i < number_of_test_runs; i++){ - parameters.emplace_back({{stochastic_distribution.parameter_name, stochastic_distribution.derive()}}); + std::vector parameters; + for (int i = 0; i < number_of_test_runs; i++) { + parameters.emplace_back( + apply>( + [](auto & type) { return type.derive(); }, + reinterpret_cast(stochastic_distribution)) + .front()); } - return stochastic_distribution.derive(); + return parameters; } }; } // namespace syntax From a38941afcb06904ed66b9d6fae102a1f50d7757f Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 6 Jan 2023 17:26:03 +0900 Subject: [PATCH 018/120] feat(interpreter): implement DeterministicSingleParameterDistribution::derive() Signed-off-by: Kotaro Yoshimoto --- .../deterministic_single_parameter_distribution.hpp | 3 ++- ...terministic_single_parameter_distribution_type.hpp | 3 ++- .../syntax/distribution_range.hpp | 7 ++++--- .../syntax/distribution_set.hpp | 11 ++++------- .../openscenario_interpreter/syntax/stochastic.hpp | 8 +++----- .../deterministic_single_parameter_distribution.cpp | 5 +++++ .../src/syntax/distribution_set.cpp | 1 - 7 files changed, 20 insertions(+), 18 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index 7bb90d254a9..b0eaab00b67 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -34,11 +34,12 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ struct DeterministicSingleParameterDistribution -: public DeterministicSingleParameterDistributionType +: public DeterministicSingleParameterDistributionType, public SingleParameterDistributionBase { const String parameter_name; explicit DeterministicSingleParameterDistribution(const pugi::xml_node &, Scope &); + auto derive() -> std::vector override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp index bd21b92dc5e..c557d617f32 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp @@ -19,6 +19,7 @@ #include #include #include +#include #include namespace openscenario_interpreter @@ -45,7 +46,7 @@ DEFINE_LAZY_VISITOR( DeterministicSingleParameterDistributionType, CASE(DistributionSet), // CASE(DistributionRange), // - CASE(UserDefinedDistribution), // +// CASE(UserDefinedDistribution), // ); } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index f6ec75a343e..c6c13d4064c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -15,6 +15,7 @@ #ifndef OPENSCENARIO_INTERPRETER__SYNTAX__DISTRIBUTION_RANGE_HPP_ #define OPENSCENARIO_INTERPRETER__SYNTAX__DISTRIBUTION_RANGE_HPP_ +#include #include #include #include @@ -32,15 +33,15 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct DistributionRange : private Scope, public ComplexType + +struct DistributionRange : private Scope, public ComplexType, public SingleParameterDistributionBase { const Double step_width; const Range range; explicit DistributionRange(const pugi::xml_node &, Scope &); - - auto derive() -> std::vector; + auto derive() -> std::vector override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index ec9fa9447c7..08bf6b70649 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -15,7 +15,9 @@ #ifndef OPENSCENARIO_INTERPRETER__DISTRIBUTION_SET_HPP_ #define OPENSCENARIO_INTERPRETER__DISTRIBUTION_SET_HPP_ +#include #include + namespace openscenario_interpreter { inline namespace syntax @@ -29,19 +31,14 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct SingleParameterList : public std::vector {}; -//using UnnamedParameterSet = std::vector; -//using UnnamedParameterList = std::vector; -//using ParameterSet = std::unordered_map; -//using ParameterList = std::vector; -struct DistributionSet : private Scope, public ComplexType +struct DistributionSet : private Scope, public ComplexType, public SingleParameterDistributionBase { const std::list elements; explicit DistributionSet(const pugi::xml_node &, Scope & scope); - auto derive() -> std::vector; + auto derive() -> std::vector override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp index 09419323578..f97c036d202 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp @@ -53,11 +53,9 @@ struct Stochastic : public ComplexType, public SingleParameterDistributionBase { std::vector parameters; for (int i = 0; i < number_of_test_runs; i++) { - parameters.emplace_back( - apply>( - [](auto & type) { return type.derive(); }, - reinterpret_cast(stochastic_distribution)) - .front()); + parameters.emplace_back(apply>( + [](auto & type) { return type.derive(); }, stochastic_distribution) + .front()); } return parameters; } diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp index a6eb09ad078..aa2db23e34d 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp @@ -25,5 +25,10 @@ DeterministicSingleParameterDistribution::DeterministicSingleParameterDistributi parameter_name(readAttribute("parameterName", node, scope)) { } +std::vector DeterministicSingleParameterDistribution::derive() +{ + return apply>( + [](auto & distribution) { return distribution.derive(); }, *this); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp index 7026ab8b623..1453b72672c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp @@ -32,6 +32,5 @@ auto DistributionSet::derive() -> std::vector } return list; } - } // namespace syntax } // namespace openscenario_interpreter From 1e8308adec2ac8e3d2a0a84c6491dd57fa84c036 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 6 Jan 2023 18:03:04 +0900 Subject: [PATCH 019/120] feat(interpreter): implement DeterministicMultiParameterDistribution::derive() Signed-off-by: Kotaro Yoshimoto --- .../syntax/deterministic_multi_parameter_distribution.hpp | 5 ++++- .../deterministic_multi_parameter_distribution_type.hpp | 4 ---- .../deterministic_single_parameter_distribution.hpp | 4 +++- .../syntax/parameter_assignment.hpp | 1 + .../syntax/parameter_value_set.hpp | 3 +-- .../syntax/value_set_distribution.hpp | 5 +++-- .../syntax/deterministic_multi_parameter_distribution.cpp | 6 ++++++ .../src/syntax/parameter_value_set.cpp | 8 ++++++-- .../src/syntax/value_set_distribution.cpp | 8 ++++++-- 9 files changed, 30 insertions(+), 14 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp index 589f36861b5..690a5eb8fdd 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp @@ -32,9 +32,12 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct DeterministicMultiParameterDistribution : public DeterministicMultiParameterDistributionType +struct DeterministicMultiParameterDistribution : public DeterministicMultiParameterDistributionType, + public MultiParameterDistributionBase { explicit DeterministicMultiParameterDistribution(const pugi::xml_node &, Scope & scope); + + auto derive() -> std::vector> override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution_type.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution_type.hpp index 3091fe51b62..a51f13be031 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution_type.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution_type.hpp @@ -37,10 +37,6 @@ struct DeterministicMultiParameterDistributionType : public ValueSetDistribution explicit DeterministicMultiParameterDistributionType(const pugi::xml_node &, Scope & scope); }; -//DEFINE_LAZY_VISITOR( -// DeterministicMultiParameterDistributionType, -// CASE(ValueSetDistribution), // -//); } // namespace syntax } // namespace openscenario_interpreter #endif // OPENSCENARIO_INTERPRETER__DETERMINISTIC_MULTI_PARAMETER_DISTRIBUTION_TYPE_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index b0eaab00b67..02ae13a4170 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -34,11 +34,13 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ struct DeterministicSingleParameterDistribution -: public DeterministicSingleParameterDistributionType, public SingleParameterDistributionBase +: public DeterministicSingleParameterDistributionType, + public SingleParameterDistributionBase { const String parameter_name; explicit DeterministicSingleParameterDistribution(const pugi::xml_node &, Scope &); + auto derive() -> std::vector override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_assignment.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_assignment.hpp index c34331b2f0c..68eac384053 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_assignment.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_assignment.hpp @@ -41,6 +41,7 @@ struct ParameterAssignment } const std::string parameterRef; + const std::string value; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp index 31a508e3a9f..f2cd3443610 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp @@ -36,8 +36,7 @@ struct ParameterValueSet : private Scope explicit ParameterValueSet(const pugi::xml_node &, Scope & scope); - // TODO: implement evaluate() - auto evaluate() -> Object; + auto evaluate() const -> std::unordered_map; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp index a47efbd11d4..f35351a3f29 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp @@ -15,6 +15,7 @@ #ifndef OPENSCENARIO_INTERPRETER__VALUE_SET_DISTRIBUTION_HPP_ #define OPENSCENARIO_INTERPRETER__VALUE_SET_DISTRIBUTION_HPP_ +#include #include #include @@ -31,13 +32,13 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct ValueSetDistribution : public Scope +struct ValueSetDistribution : public Scope, public MultiParameterDistributionBase { const std::list parameter_value_sets; explicit ValueSetDistribution(const pugi::xml_node &, Scope & scope); - auto evaluate() -> Object; + auto derive() -> std::vector> override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp index 88ca2a52b9c..28e909ac100 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp @@ -24,5 +24,11 @@ DeterministicMultiParameterDistribution::DeterministicMultiParameterDistribution : DeterministicMultiParameterDistributionType(node, scope) { } + +std::vector> +DeterministicMultiParameterDistribution::derive() +{ + return DeterministicMultiParameterDistributionType::derive(); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp b/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp index 6563a635cd8..96389ea6913 100644 --- a/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp @@ -26,9 +26,13 @@ ParameterValueSet::ParameterValueSet( { } -auto ParameterValueSet::evaluate() -> Object +auto ParameterValueSet::evaluate() const -> std::unordered_map { - throw common::Error("ParameterValueSet is not implemented yet"); + std::unordered_map parameters; + for (const auto & parameter : parameter_assignments) { + parameters[parameter.parameterRef] = make(parameter.value); + } + return parameters; } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp index 97035fa76f0..9c7c91b70b2 100644 --- a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp @@ -26,9 +26,13 @@ ValueSetDistribution::ValueSetDistribution( { } -auto ValueSetDistribution::evaluate() -> Object +auto ValueSetDistribution::derive() -> std::vector> { - throw common::Error("ValueSetDistribution is not implemented yet"); + std::vector> parameters; + for (const auto & parameter_value_set : parameter_value_sets) { + parameters.emplace_back(parameter_value_set.evaluate()); + } + return parameters; } } // namespace syntax } // namespace openscenario_interpreter From 2d696d34aece44c4de237cfd87c6a96be299787e Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 9 Feb 2023 18:02:52 +0900 Subject: [PATCH 020/120] feat(interpreter/ParameterValueDistribution): implement distribution merging function --- .../parameter_distribution.hpp | 47 ++++++++++++++-- .../src/parameter_distribution.cpp | 53 +++++++++++++++++++ 2 files changed, 97 insertions(+), 3 deletions(-) create mode 100644 openscenario/openscenario_interpreter/src/parameter_distribution.cpp diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp index 0ae14fad507..40d4b97e2f2 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -20,14 +20,55 @@ namespace openscenario_interpreter { + +using ParameterList = std::unordered_map; +using ParameterListSharedPtr = std::shared_ptr; +using ParameterDistribution = std::vector; +using SingleParameterDistribution = std::vector; + struct SingleParameterDistributionBase { - virtual auto derive() -> std::vector = 0; + virtual auto derive() -> SingleParameterDistribution = 0; }; struct MultiParameterDistributionBase { - virtual auto derive() -> std::vector> = 0; + virtual auto derive() -> ParameterDistribution = 0; +}; + +auto mergeParameterDistributionImpl( + const ParameterDistribution & distribution, std::string single_parameter_name, + SingleParameterDistribution && single_distribution) -> ParameterDistribution; + +auto mergeParameterDistributionImpl( + ParameterDistribution distribution, ParameterDistribution additional_distribution) + -> ParameterDistribution; + +template +ParameterDistribution mergeParameterDistribution( + ParameterDistribution && distribution, DistributionT && x) +{ + return mergeParameterDistributionImpl(distribution, x.derive()); +} + +template +ParameterDistribution mergeParameterDistribution( + ParameterDistribution && distribution, DistributionT && x, Ts &&... xs) +{ + return mergeParameterDistribution( + distribution, std::forward(x), + mergeParameterDistribution(distribution, std::forward(xs)...)); +} + +struct ParameterDistributionMergerBase +{ + template + explicit ParameterDistributionMergerBase(Ts... xs) + : distribution(mergeParameterDistribution(ParameterDistribution(), xs...)) + { + } + + ParameterDistribution distribution; }; } // namespace openscenario_interpreter -#endif //OPENSCENARIO_INTERPRETER__PARAMETER_DISTRIBUTION_HPP_ +#endif // OPENSCENARIO_INTERPRETER__PARAMETER_DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp new file mode 100644 index 00000000000..b19619988f8 --- /dev/null +++ b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp @@ -0,0 +1,53 @@ +// 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 openscenario_interpreter::mergeParameterDistributionImpl( + const ParameterDistribution & distribution, std::string single_parameter_name, + SingleParameterDistribution && single_distribution) -> ParameterDistribution +{ + ParameterDistribution merged_distribution; + merged_distribution.reserve(distribution.size() * single_distribution.size()); + + for (const auto & single_parameter_value : single_distribution) { + for (const auto & list : distribution) { + merged_distribution.emplace_back(list); + merged_distribution.back()->at(single_parameter_name) = single_parameter_value; + } + } + + return merged_distribution; +} +auto mergeParameterDistributionImpl( + std::vector>> distribution, + std::vector>> additional_distribution) + -> std::vector>> +{ + ParameterDistribution merged_distribution; + merged_distribution.reserve(distribution.size() * additional_distribution.size()); + + for (const auto & additional_parameter_list : additional_distribution) { + for (const auto & list : distribution) { + merged_distribution.emplace_back(list); + merged_distribution.back()->insert( + additional_parameter_list->begin(), additional_parameter_list->end()); + } + } + + return merged_distribution; +} +} From 7fedfcef726999f285f17055b1aef8bc32ae1486 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 9 Feb 2023 18:03:31 +0900 Subject: [PATCH 021/120] feat(interpreter/ParameterValueDistribution): use new struct for distributions --- .../syntax/deterministic_multi_parameter_distribution.hpp | 2 +- .../openscenario_interpreter/syntax/parameter_value_set.hpp | 2 +- .../syntax/value_set_distribution.hpp | 2 +- .../syntax/deterministic_multi_parameter_distribution.cpp | 2 +- .../src/syntax/parameter_value_set.cpp | 6 +++--- .../src/syntax/value_set_distribution.cpp | 4 ++-- 6 files changed, 9 insertions(+), 9 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp index 690a5eb8fdd..742fec30525 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp @@ -37,7 +37,7 @@ struct DeterministicMultiParameterDistribution : public DeterministicMultiParame { explicit DeterministicMultiParameterDistribution(const pugi::xml_node &, Scope & scope); - auto derive() -> std::vector> override; + auto derive() -> ParameterDistribution override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp index f2cd3443610..61803c3571d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp @@ -36,7 +36,7 @@ struct ParameterValueSet : private Scope explicit ParameterValueSet(const pugi::xml_node &, Scope & scope); - auto evaluate() const -> std::unordered_map; + auto evaluate() const -> std::shared_ptr>; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp index f35351a3f29..15f0e7dd388 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp @@ -38,7 +38,7 @@ struct ValueSetDistribution : public Scope, public MultiParameterDistributionBas explicit ValueSetDistribution(const pugi::xml_node &, Scope & scope); - auto derive() -> std::vector> override; + auto derive() -> ParameterDistribution override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp index 28e909ac100..a97471f53a8 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp @@ -25,7 +25,7 @@ DeterministicMultiParameterDistribution::DeterministicMultiParameterDistribution { } -std::vector> +ParameterDistribution DeterministicMultiParameterDistribution::derive() { return DeterministicMultiParameterDistributionType::derive(); diff --git a/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp b/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp index 96389ea6913..642cb21bb05 100644 --- a/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp @@ -26,11 +26,11 @@ ParameterValueSet::ParameterValueSet( { } -auto ParameterValueSet::evaluate() const -> std::unordered_map +auto ParameterValueSet::evaluate() const -> std::shared_ptr> { - std::unordered_map parameters; + std::shared_ptr> parameters; for (const auto & parameter : parameter_assignments) { - parameters[parameter.parameterRef] = make(parameter.value); + parameters->at(parameter.parameterRef) = make(parameter.value); } return parameters; } diff --git a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp index 9c7c91b70b2..eafe1a64f2c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp @@ -26,9 +26,9 @@ ValueSetDistribution::ValueSetDistribution( { } -auto ValueSetDistribution::derive() -> std::vector> +auto ValueSetDistribution::derive() -> ParameterDistribution { - std::vector> parameters; + ParameterDistribution parameters; for (const auto & parameter_value_set : parameter_value_sets) { parameters.emplace_back(parameter_value_set.evaluate()); } From 9632f2581ba91fc3118aa42dc624b4d589c10ab8 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 9 Feb 2023 20:09:52 +0900 Subject: [PATCH 022/120] chore: apply linter --- .../deterministic_single_parameter_distribution_type.hpp | 8 ++++---- .../syntax/normal_distribution.hpp | 4 +++- .../syntax/poisson_distribution.hpp | 6 ++++-- .../syntax/stochastic_distribution.hpp | 2 +- .../syntax/uniform_distribution.hpp | 4 +++- .../src/parameter_distribution.cpp | 5 +++-- .../syntax/deterministic_multi_parameter_distribution.cpp | 3 +-- 7 files changed, 19 insertions(+), 13 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp index c557d617f32..081c003e6f8 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp @@ -15,11 +15,11 @@ #ifndef OPENSCENARIO_INTERPRETER__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_TYPE_HPP_ #define OPENSCENARIO_INTERPRETER__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_TYPE_HPP_ +#include #include #include #include #include -#include #include namespace openscenario_interpreter @@ -44,9 +44,9 @@ struct DeterministicSingleParameterDistributionType : public Group DEFINE_LAZY_VISITOR( DeterministicSingleParameterDistributionType, - CASE(DistributionSet), // - CASE(DistributionRange), // -// CASE(UserDefinedDistribution), // + CASE(DistributionSet), // + CASE(DistributionRange), // + // CASE(UserDefinedDistribution), // ); } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp index cb479fb8380..d5395cac07e 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp @@ -38,7 +38,9 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ -struct NormalDistribution : public ComplexType, private Scope, public SingleParameterDistributionBase +struct NormalDistribution : public ComplexType, + private Scope, + public SingleParameterDistributionBase { const Range range; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index eede45d8478..fa5085543eb 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -15,11 +15,11 @@ #ifndef OPENSCENARIO_INTERPRETER__POISSON_DISTRIBUTION_HPP_ #define OPENSCENARIO_INTERPRETER__POISSON_DISTRIBUTION_HPP_ +#include #include #include #include #include -#include namespace openscenario_interpreter { @@ -35,7 +35,9 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct PoissonDistribution : public ComplexType, private Scope, public SingleParameterDistributionBase +struct PoissonDistribution : public ComplexType, + private Scope, + public SingleParameterDistributionBase { const Range range; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp index e2788991dda..4a2390e5696 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp @@ -15,10 +15,10 @@ #ifndef OPENSCENARIO_INTERPRETER__STOCHASTIC_DISTRIBUTION_HPP_ #define OPENSCENARIO_INTERPRETER__STOCHASTIC_DISTRIBUTION_HPP_ +#include #include #include #include -#include namespace openscenario_interpreter { diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index f2152a37ff6..dd4ca7b33cc 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -33,7 +33,9 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct UniformDistribution : public ComplexType, private Scope, public SingleParameterDistributionBase +struct UniformDistribution : public ComplexType, + private Scope, + public SingleParameterDistributionBase { const Range range; diff --git a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp index b19619988f8..c7236ba95b4 100644 --- a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp @@ -14,7 +14,8 @@ #include -namespace openscenario_interpreter{ +namespace openscenario_interpreter +{ auto openscenario_interpreter::mergeParameterDistributionImpl( const ParameterDistribution & distribution, std::string single_parameter_name, @@ -50,4 +51,4 @@ auto mergeParameterDistributionImpl( return merged_distribution; } -} +} // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp index a97471f53a8..ff268236376 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp @@ -25,8 +25,7 @@ DeterministicMultiParameterDistribution::DeterministicMultiParameterDistribution { } -ParameterDistribution -DeterministicMultiParameterDistribution::derive() +ParameterDistribution DeterministicMultiParameterDistribution::derive() { return DeterministicMultiParameterDistributionType::derive(); } From a98e3d46305b9f3d7d1c3958914e47ea89cb470c Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 10 Feb 2023 00:50:24 +0900 Subject: [PATCH 023/120] chore: apply linter --- .../syntax/stochastic_distribution_type.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp index 206b15c3d47..3b7543e79aa 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp @@ -54,7 +54,7 @@ DEFINE_LAZY_VISITOR( CASE(UniformDistribution), // CASE(PoissonDistribution), // CASE(Histogram), // -// CASE(UserDefinedDistribution), // + // CASE(UserDefinedDistribution), // ); } // namespace syntax } // namespace openscenario_interpreter From c808580d6d5d309f00582ba83f237c4e60011fc9 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 10 Feb 2023 10:03:05 +0900 Subject: [PATCH 024/120] chore: apply linter --- .../openscenario_interpreter/parameter_distribution.hpp | 1 - .../openscenario_interpreter/src/parameter_distribution.cpp | 4 +--- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp index 40d4b97e2f2..4b84ef8d7a7 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -20,7 +20,6 @@ namespace openscenario_interpreter { - using ParameterList = std::unordered_map; using ParameterListSharedPtr = std::shared_ptr; using ParameterDistribution = std::vector; diff --git a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp index c7236ba95b4..3c60226d089 100644 --- a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp @@ -16,7 +16,6 @@ namespace openscenario_interpreter { - auto openscenario_interpreter::mergeParameterDistributionImpl( const ParameterDistribution & distribution, std::string single_parameter_name, SingleParameterDistribution && single_distribution) -> ParameterDistribution @@ -30,9 +29,9 @@ auto openscenario_interpreter::mergeParameterDistributionImpl( merged_distribution.back()->at(single_parameter_name) = single_parameter_value; } } - return merged_distribution; } + auto mergeParameterDistributionImpl( std::vector>> distribution, std::vector>> additional_distribution) @@ -48,7 +47,6 @@ auto mergeParameterDistributionImpl( additional_parameter_list->begin(), additional_parameter_list->end()); } } - return merged_distribution; } } // namespace openscenario_interpreter From 9d4fe5babbd91234f22635148a3d28c5974faf17 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 10 Feb 2023 14:57:43 +0900 Subject: [PATCH 025/120] feat(interpreter/ParameterValueDistribution): categorize various classes related to distribution by specify base class --- .../parameter_distribution.hpp | 46 +++++++++++++------ ...rministic_multi_parameter_distribution.hpp | 2 +- ...ministic_single_parameter_distribution.hpp | 4 +- .../syntax/distribution_range.hpp | 3 +- .../syntax/distribution_set.hpp | 2 +- ...ministic_single_parameter_distribution.cpp | 12 +++-- .../src/syntax/distribution_range.cpp | 8 ++-- .../src/syntax/distribution_set.cpp | 8 ++-- 8 files changed, 56 insertions(+), 29 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp index 4b84ef8d7a7..6fc7b90d1ce 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -20,14 +20,21 @@ namespace openscenario_interpreter { +// data container types of distribution using ParameterList = std::unordered_map; using ParameterListSharedPtr = std::shared_ptr; using ParameterDistribution = std::vector; -using SingleParameterDistribution = std::vector; +using SingleUnnamedParameterDistribution = std::vector; +struct SingleParameterDistribution +{ + std::string name; + SingleUnnamedParameterDistribution distribution; +}; +// generator types distribution struct SingleParameterDistributionBase { - virtual auto derive() -> SingleParameterDistribution = 0; + virtual auto derive() -> SingleUnnamedParameterDistribution = 0; }; struct MultiParameterDistributionBase @@ -35,12 +42,23 @@ struct MultiParameterDistributionBase virtual auto derive() -> ParameterDistribution = 0; }; +// container types of distribution data generator +struct SingleParameterDistributionContainer +{ + virtual auto derive() -> SingleParameterDistribution = 0; +}; + +struct MultiParameterDistributionContainer +{ + virtual auto derive() -> ParameterDistribution = 0; +}; + auto mergeParameterDistributionImpl( - const ParameterDistribution & distribution, std::string single_parameter_name, - SingleParameterDistribution && single_distribution) -> ParameterDistribution; + ParameterDistribution && distribution, SingleParameterDistribution && single_distribution) + -> ParameterDistribution; auto mergeParameterDistributionImpl( - ParameterDistribution distribution, ParameterDistribution additional_distribution) + ParameterDistribution && distribution, ParameterDistribution && additional_distribution) -> ParameterDistribution; template @@ -59,15 +77,17 @@ ParameterDistribution mergeParameterDistribution( mergeParameterDistribution(distribution, std::forward(xs)...)); } -struct ParameterDistributionMergerBase +template +ParameterDistribution mergeParameterDistribution( + ParameterDistribution && distribution, const std::list & distribution_list) { - template - explicit ParameterDistributionMergerBase(Ts... xs) - : distribution(mergeParameterDistribution(ParameterDistribution(), xs...)) - { + for (const auto & additional_distribution : distribution_list) { + distribution = mergeParameterDistributionImpl( + distribution, + apply( + [](const auto & distribution) { return distribution.derive(); }, additional_distribution)); } - - ParameterDistribution distribution; -}; + return distribution; +} } // namespace openscenario_interpreter #endif // OPENSCENARIO_INTERPRETER__PARAMETER_DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp index 742fec30525..c51207ab6d9 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp @@ -33,7 +33,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ struct DeterministicMultiParameterDistribution : public DeterministicMultiParameterDistributionType, - public MultiParameterDistributionBase + public MultiParameterDistributionContainer { explicit DeterministicMultiParameterDistribution(const pugi::xml_node &, Scope & scope); diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index 02ae13a4170..ac086789c3d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -35,13 +35,13 @@ inline namespace syntax * -------------------------------------------------------------------------- */ struct DeterministicSingleParameterDistribution : public DeterministicSingleParameterDistributionType, - public SingleParameterDistributionBase + public SingleParameterDistributionContainer { const String parameter_name; explicit DeterministicSingleParameterDistribution(const pugi::xml_node &, Scope &); - auto derive() -> std::vector override; + auto derive() -> SingleParameterDistribution override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index c6c13d4064c..d8ae87e1a20 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -41,7 +41,8 @@ struct DistributionRange : private Scope, public ComplexType, public SingleParam const Range range; explicit DistributionRange(const pugi::xml_node &, Scope &); - auto derive() -> std::vector override; + + auto derive() -> SingleUnnamedParameterDistribution override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index 08bf6b70649..15c4a150b07 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -38,7 +38,7 @@ struct DistributionSet : private Scope, public ComplexType, public SingleParamet explicit DistributionSet(const pugi::xml_node &, Scope & scope); - auto derive() -> std::vector override; + auto derive() -> SingleUnnamedParameterDistribution override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp index aa2db23e34d..b1c9cfa485d 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp @@ -25,10 +25,16 @@ DeterministicSingleParameterDistribution::DeterministicSingleParameterDistributi parameter_name(readAttribute("parameterName", node, scope)) { } -std::vector DeterministicSingleParameterDistribution::derive() +SingleParameterDistribution DeterministicSingleParameterDistribution::derive() { - return apply>( - [](auto & distribution) { return distribution.derive(); }, *this); + return apply( + [this](auto & unnamed_distribution) { + SingleParameterDistribution distribution; + distribution.name = parameter_name; + distribution.distribution = unnamed_distribution.derive(); + return distribution; + }, + *this); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp index 329ae6de6ec..fbe0f16212b 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp @@ -26,14 +26,14 @@ DistributionRange::DistributionRange(const pugi::xml_node & node, Scope & scope) { } -auto DistributionRange::derive() -> std::vector +auto DistributionRange::derive() -> SingleUnnamedParameterDistribution { - std::vector list; + SingleUnnamedParameterDistribution unnamed_distribution; for (double parameter = range.lower_limit; parameter <= range.upper_limit; parameter += step_width) { - list.emplace_back(make(parameter)); + unnamed_distribution.emplace_back(make(parameter)); } - return list; + return unnamed_distribution; } } // namespace syntax diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp index 1453b72672c..7a023200e43 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp @@ -24,13 +24,13 @@ DistributionSet::DistributionSet(const pugi::xml_node & node, Scope & scope) { } -auto DistributionSet::derive() -> std::vector +auto DistributionSet::derive() -> SingleUnnamedParameterDistribution { - std::vector list; + SingleUnnamedParameterDistribution distribution; for (const auto & element : elements) { - list.emplace_back(make(element.value)); + distribution.emplace_back(make(element.value)); } - return list; + return distribution; } } // namespace syntax } // namespace openscenario_interpreter From a85608ac8eadd258d108d25ba9a814f437963963 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 10 Feb 2023 18:27:12 +0900 Subject: [PATCH 026/120] fix(CMake): add missing cpp file to target --- openscenario/openscenario_interpreter/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/openscenario/openscenario_interpreter/CMakeLists.txt b/openscenario/openscenario_interpreter/CMakeLists.txt index 9e5655daef5..6985b5c1537 100644 --- a/openscenario/openscenario_interpreter/CMakeLists.txt +++ b/openscenario/openscenario_interpreter/CMakeLists.txt @@ -29,6 +29,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/object.cpp src/evaluate.cpp src/openscenario_interpreter.cpp + src/parameter_distribution.cpp src/record.cpp src/scope.cpp) From bc9a76f570551040af4e0772625e5bcb46035436 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 10 Feb 2023 18:33:11 +0900 Subject: [PATCH 027/120] refactor(interpreter/ParameterValueDistribution): merge ParameterDistributionContainer classes --- .../parameter_distribution.hpp | 31 ++----------------- ...rministic_multi_parameter_distribution.hpp | 2 +- ...ministic_single_parameter_distribution.hpp | 4 +-- .../src/parameter_distribution.cpp | 23 ++------------ ...ministic_single_parameter_distribution.cpp | 13 +++++--- 5 files changed, 17 insertions(+), 56 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp index 6fc7b90d1ce..3bd3ebf3cb4 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -43,40 +43,15 @@ struct MultiParameterDistributionBase }; // container types of distribution data generator -struct SingleParameterDistributionContainer -{ - virtual auto derive() -> SingleParameterDistribution = 0; -}; - -struct MultiParameterDistributionContainer +struct ParameterDistributionContainer { virtual auto derive() -> ParameterDistribution = 0; }; -auto mergeParameterDistributionImpl( - ParameterDistribution && distribution, SingleParameterDistribution && single_distribution) +auto mergeParameterDistribution( + ParameterDistribution & distribution, ParameterDistribution && additional_distribution) -> ParameterDistribution; -auto mergeParameterDistributionImpl( - ParameterDistribution && distribution, ParameterDistribution && additional_distribution) - -> ParameterDistribution; - -template -ParameterDistribution mergeParameterDistribution( - ParameterDistribution && distribution, DistributionT && x) -{ - return mergeParameterDistributionImpl(distribution, x.derive()); -} - -template -ParameterDistribution mergeParameterDistribution( - ParameterDistribution && distribution, DistributionT && x, Ts &&... xs) -{ - return mergeParameterDistribution( - distribution, std::forward(x), - mergeParameterDistribution(distribution, std::forward(xs)...)); -} - template ParameterDistribution mergeParameterDistribution( ParameterDistribution && distribution, const std::list & distribution_list) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp index c51207ab6d9..0cb03b365fd 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp @@ -33,7 +33,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ struct DeterministicMultiParameterDistribution : public DeterministicMultiParameterDistributionType, - public MultiParameterDistributionContainer + public ParameterDistributionContainer { explicit DeterministicMultiParameterDistribution(const pugi::xml_node &, Scope & scope); diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index ac086789c3d..3ac7b9c9515 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -35,13 +35,13 @@ inline namespace syntax * -------------------------------------------------------------------------- */ struct DeterministicSingleParameterDistribution : public DeterministicSingleParameterDistributionType, - public SingleParameterDistributionContainer + public ParameterDistributionContainer { const String parameter_name; explicit DeterministicSingleParameterDistribution(const pugi::xml_node &, Scope &); - auto derive() -> SingleParameterDistribution override; + auto derive() -> ParameterDistribution override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp index 3c60226d089..4bbdd04e8ca 100644 --- a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp @@ -16,26 +16,9 @@ namespace openscenario_interpreter { -auto openscenario_interpreter::mergeParameterDistributionImpl( - const ParameterDistribution & distribution, std::string single_parameter_name, - SingleParameterDistribution && single_distribution) -> ParameterDistribution -{ - ParameterDistribution merged_distribution; - merged_distribution.reserve(distribution.size() * single_distribution.size()); - - for (const auto & single_parameter_value : single_distribution) { - for (const auto & list : distribution) { - merged_distribution.emplace_back(list); - merged_distribution.back()->at(single_parameter_name) = single_parameter_value; - } - } - return merged_distribution; -} - -auto mergeParameterDistributionImpl( - std::vector>> distribution, - std::vector>> additional_distribution) - -> std::vector>> +auto mergeParameterDistribution( + ParameterDistribution & distribution, ParameterDistribution && additional_distribution) + -> ParameterDistribution { ParameterDistribution merged_distribution; merged_distribution.reserve(distribution.size() * additional_distribution.size()); diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp index b1c9cfa485d..1ec0c8fbc12 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp @@ -25,13 +25,16 @@ DeterministicSingleParameterDistribution::DeterministicSingleParameterDistributi parameter_name(readAttribute("parameterName", node, scope)) { } -SingleParameterDistribution DeterministicSingleParameterDistribution::derive() + +ParameterDistribution DeterministicSingleParameterDistribution::derive() { - return apply( + return apply( [this](auto & unnamed_distribution) { - SingleParameterDistribution distribution; - distribution.name = parameter_name; - distribution.distribution = unnamed_distribution.derive(); + ParameterDistribution distribution; + for (const auto & parameter : unnamed_distribution.derive()) { + distribution.emplace_back( + std::make_shared(ParameterList{{parameter_name, make(parameter)}})); + } return distribution; }, *this); From 75db7e85d1239be354c6b44ecf29bdf6af23eea7 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 10 Feb 2023 18:33:51 +0900 Subject: [PATCH 028/120] refactor(interpreter/ParameterValueDistribution): add process for empty distribution --- .../openscenario_interpreter/src/parameter_distribution.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp index 4bbdd04e8ca..dda920f3292 100644 --- a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp @@ -20,6 +20,9 @@ auto mergeParameterDistribution( ParameterDistribution & distribution, ParameterDistribution && additional_distribution) -> ParameterDistribution { + if (distribution.empty()) { + distribution.emplace_back(ParameterListSharedPtr()); + } ParameterDistribution merged_distribution; merged_distribution.reserve(distribution.size() * additional_distribution.size()); From d9b2494cd59c9cb1292d2b211baad2b1dd7ca639 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 10 Feb 2023 18:35:06 +0900 Subject: [PATCH 029/120] feat(interpreter/ParameterValueDistribution): implement derive function in Stochastic and Deterministic class --- .../parameter_distribution.hpp | 20 +++++++++---------- .../syntax/deterministic.hpp | 5 ++++- .../syntax/stochastic.hpp | 15 +++++++------- .../syntax/stochastic_distribution.hpp | 5 ++++- .../src/syntax/deterministic.cpp | 11 ++++++++++ .../src/syntax/stochastic_distribution.cpp | 14 +++++++++++++ 6 files changed, 50 insertions(+), 20 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp index 3bd3ebf3cb4..6159ffb3661 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -15,6 +15,9 @@ #ifndef OPENSCENARIO_INTERPRETER__PARAMETER_DISTRIBUTION_HPP_ #define OPENSCENARIO_INTERPRETER__PARAMETER_DISTRIBUTION_HPP_ +#include +#include +#include #include #include @@ -25,11 +28,6 @@ using ParameterList = std::unordered_map; using ParameterListSharedPtr = std::shared_ptr; using ParameterDistribution = std::vector; using SingleUnnamedParameterDistribution = std::vector; -struct SingleParameterDistribution -{ - std::string name; - SingleUnnamedParameterDistribution distribution; -}; // generator types distribution struct SingleParameterDistributionBase @@ -53,16 +51,18 @@ auto mergeParameterDistribution( -> ParameterDistribution; template -ParameterDistribution mergeParameterDistribution( - ParameterDistribution && distribution, const std::list & distribution_list) +ParameterDistribution mergeParameterDistributionList( + const ParameterDistribution & base_distribution, + const std::list & distribution_list) { + ParameterDistribution merged_distribution{base_distribution}; for (const auto & additional_distribution : distribution_list) { - distribution = mergeParameterDistributionImpl( - distribution, + merged_distribution = mergeParameterDistribution( + merged_distribution, apply( [](const auto & distribution) { return distribution.derive(); }, additional_distribution)); } - return distribution; + return merged_distribution; } } // namespace openscenario_interpreter #endif // OPENSCENARIO_INTERPRETER__PARAMETER_DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp index e40f96c6674..ead4f0e68ce 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp @@ -15,6 +15,7 @@ #ifndef OPENSCENARIO_INTERPRETER__DETERMINISTIC_HPP_ #define OPENSCENARIO_INTERPRETER__DETERMINISTIC_HPP_ +#include #include #include #include @@ -32,11 +33,13 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct Deterministic +struct Deterministic : public ParameterDistributionContainer { const std::list deterministic_parameter_distributions; explicit Deterministic(const pugi::xml_node &, Scope & scope); + + auto derive() -> ParameterDistribution override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp index f97c036d202..57c611541ae 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp @@ -39,7 +39,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ -struct Stochastic : public ComplexType, public SingleParameterDistributionBase +struct Stochastic : public ComplexType, public ParameterDistributionContainer { const UnsignedInt number_of_test_runs; @@ -49,15 +49,14 @@ struct Stochastic : public ComplexType, public SingleParameterDistributionBase explicit Stochastic(const pugi::xml_node &, Scope & scope); - auto derive() -> std::vector override + auto derive() -> ParameterDistribution override { - std::vector parameters; - for (int i = 0; i < number_of_test_runs; i++) { - parameters.emplace_back(apply>( - [](auto & type) { return type.derive(); }, stochastic_distribution) - .front()); + ParameterDistribution distribution; + for (size_t i = 0; i < number_of_test_runs; i++) { + auto derived = stochastic_distribution.derive(); + distribution.insert(distribution.end(), derived.begin(), derived.end()); } - return parameters; + return distribution; } }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp index 4a2390e5696..fbded25eec6 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp @@ -34,11 +34,14 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct StochasticDistribution : public StochasticDistributionType +struct StochasticDistribution : public StochasticDistributionType, + public ParameterDistributionContainer { const String parameter_name; explicit StochasticDistribution(const pugi::xml_node &, Scope & scope); + + auto derive() -> ParameterDistribution override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp index d02ba05e42a..d24c9c069cd 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp @@ -24,5 +24,16 @@ Deterministic::Deterministic(const pugi::xml_node & node, Scope & scope) readGroups(node, scope)) { } +ParameterDistribution Deterministic::derive() +{ + ParameterDistribution distribution; + for (auto additional_distribution : deterministic_parameter_distributions) { + distribution = mergeParameterDistribution( + distribution, + apply( + [](auto & distribution) { return distribution.derive(); }, additional_distribution)); + } + return distribution; +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp index f4b25346a0d..c83555ec530 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp @@ -24,5 +24,19 @@ StochasticDistribution::StochasticDistribution(const pugi::xml_node & node, Scop parameter_name(readAttribute("parameterName", node, scope)) { } + +auto StochasticDistribution::derive() -> ParameterDistribution +{ + return apply( + [this](auto & unnamed_distribution) { + ParameterDistribution distribution; + for (const auto & parameter : unnamed_distribution.derive()) { + distribution.emplace_back( + std::make_shared(ParameterList{{parameter_name, make(parameter)}})); + } + return distribution; + }, + *this); +} } // namespace syntax } // namespace openscenario_interpreter From 4206d8a75f562810d5c955c8879c2b1e57f6fa18 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 10 Feb 2023 18:41:24 +0900 Subject: [PATCH 030/120] feat(interpreter/ParameterValueDistribution): implement derive function in ParameterValueDistribution class --- .../syntax/parameter_value_distribution.hpp | 5 ++++- .../src/syntax/parameter_value_distribution.cpp | 6 ++++++ 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp index 4722301a4fc..8197cf17d2a 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp @@ -32,11 +32,14 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct ParameterValueDistribution : public DistributionDefinition +struct ParameterValueDistribution : public DistributionDefinition, + public ParameterDistributionContainer { const File scenario_file; explicit ParameterValueDistribution(const pugi::xml_node &, Scope & scope); + + auto derive() -> ParameterDistribution override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp index 63a2c7eb5ad..e4130e75d3c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp @@ -24,5 +24,11 @@ ParameterValueDistribution::ParameterValueDistribution( : DistributionDefinition(node, scope), scenario_file(readElement("ScenarioFile", node, scope)) { } + +ParameterDistribution ParameterValueDistribution::derive() +{ + return apply( + [](auto & distribution) { return distribution.derive(); }, *this); +} } // namespace syntax } // namespace openscenario_interpreter From 2541a2552ceebbbd3d435dbd1bda586003bb2492 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 20 Feb 2023 09:57:09 +0900 Subject: [PATCH 031/120] fix(interpreter/ParameterValueDistribution): fix element name --- .../src/syntax/parameter_value_distribution_definition.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution_definition.cpp b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution_definition.cpp index a95da7efc4e..3deb58221a4 100644 --- a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution_definition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution_definition.cpp @@ -22,7 +22,7 @@ inline namespace syntax ParameterValueDistributionDefinition::ParameterValueDistributionDefinition( const pugi::xml_node & node, Scope & scope) : ParameterValueDistribution( - readElement("parameterValueDistribution", node, scope)) + readElement("ParameterValueDistribution", node, scope)) { } } // namespace syntax From 1fc9dcbee899225383a1936d515014fd98f89485 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 20 Feb 2023 09:58:51 +0900 Subject: [PATCH 032/120] fix(interpreter/ParameterValueDistribution): support list of DeterministicSingleParameterDistributionType --- ...ministic_single_parameter_distribution.hpp | 7 ++-- ...ministic_single_parameter_distribution.cpp | 32 ++++++++++++------- 2 files changed, 24 insertions(+), 15 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index 3ac7b9c9515..08ccb4cfe1c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -33,12 +33,13 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct DeterministicSingleParameterDistribution -: public DeterministicSingleParameterDistributionType, - public ParameterDistributionContainer +struct DeterministicSingleParameterDistribution : public ParameterDistributionContainer { const String parameter_name; + const std::list + deterministic_single_parameter_distributions; + explicit DeterministicSingleParameterDistribution(const pugi::xml_node &, Scope &); auto derive() -> ParameterDistribution override; diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp index 1ec0c8fbc12..8ee7a912dea 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp @@ -21,23 +21,31 @@ inline namespace syntax { DeterministicSingleParameterDistribution::DeterministicSingleParameterDistribution( const pugi::xml_node & node, Scope & scope) -: DeterministicSingleParameterDistributionType(node, scope), - parameter_name(readAttribute("parameterName", node, scope)) +: parameter_name(readAttribute("parameterName", node, scope)), + deterministic_single_parameter_distributions( + readGroups(node, scope)) { } ParameterDistribution DeterministicSingleParameterDistribution::derive() { - return apply( - [this](auto & unnamed_distribution) { - ParameterDistribution distribution; - for (const auto & parameter : unnamed_distribution.derive()) { - distribution.emplace_back( - std::make_shared(ParameterList{{parameter_name, make(parameter)}})); - } - return distribution; - }, - *this); + std::cout << "DeterministicSingleParameterDistribution::derive" << std::endl; + ParameterDistribution distribution; + for (auto additional_distribution : deterministic_single_parameter_distributions) { + std::cout << "additional_distribution: " << std::endl; + distribution = mergeParameterDistribution( + distribution, apply( + [this](auto & unnamed_distribution) { + ParameterDistribution distribution; + for (const auto & parameter : unnamed_distribution.derive()) { + distribution.emplace_back(std::make_shared( + ParameterList{{parameter_name, make(parameter)}})); + } + return distribution; + }, + additional_distribution)); + } + return distribution; } } // namespace syntax } // namespace openscenario_interpreter From a801e7cddb9070f4cd3c7449507bb8c2188dbc78 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 21 Feb 2023 17:32:28 +0900 Subject: [PATCH 033/120] fix(interpreter/ParameterValueDistribution): fix implementation of mergeParameterDistribution function --- .../src/parameter_distribution.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp index dda920f3292..d5d763ece69 100644 --- a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp @@ -21,16 +21,16 @@ auto mergeParameterDistribution( -> ParameterDistribution { if (distribution.empty()) { - distribution.emplace_back(ParameterListSharedPtr()); + distribution.emplace_back(std::make_shared()); } + ParameterDistribution merged_distribution; merged_distribution.reserve(distribution.size() * additional_distribution.size()); - - for (const auto & additional_parameter_list : additional_distribution) { - for (const auto & list : distribution) { - merged_distribution.emplace_back(list); - merged_distribution.back()->insert( - additional_parameter_list->begin(), additional_parameter_list->end()); + for (const ParameterListSharedPtr additional_parameter_list : additional_distribution) { + for (const ParameterListSharedPtr list : distribution) { + auto merged_list = ParameterList{*list}; + merged_list.insert(additional_parameter_list->cbegin(), additional_parameter_list->cend()); + merged_distribution.emplace_back(std::make_shared(merged_list)); } } return merged_distribution; From b548822fa3b6a495b29ee8a9ec186e8df04eb814 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 21 Feb 2023 17:33:41 +0900 Subject: [PATCH 034/120] fix(interpreter/ParameterValueDistribution): fix choice argument --- .../deterministic_single_parameter_distribution_type.cpp | 4 ++-- .../src/syntax/open_scenario_category.cpp | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution_type.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution_type.cpp index 76296e5e95d..cce7e14edac 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution_type.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution_type.cpp @@ -20,10 +20,10 @@ namespace openscenario_interpreter inline namespace syntax { DeterministicSingleParameterDistributionType::DeterministicSingleParameterDistributionType( - const pugi::xml_node & node, Scope & scope) + const pugi::xml_node & tree, Scope & scope) // clang-format off : Group( - choice(node, + choice(tree, std::make_pair("DistributionSet", [&](auto && node){ return make(node, scope);}), std::make_pair("DistributionRange", [&](auto && node){ return make(node, scope);}), std::make_pair("UserDefinedDistribution", [&](auto && node){ return make(node, scope);}))) diff --git a/openscenario/openscenario_interpreter/src/syntax/open_scenario_category.cpp b/openscenario/openscenario_interpreter/src/syntax/open_scenario_category.cpp index 2c4d6e898c6..c065a989c5f 100644 --- a/openscenario/openscenario_interpreter/src/syntax/open_scenario_category.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/open_scenario_category.cpp @@ -25,9 +25,9 @@ OpenScenarioCategory::OpenScenarioCategory(const pugi::xml_node & tree, Scope & : Group( // clang-format off choice(tree, - std::make_pair("Storyboard", [&](auto && ) { return make(tree, scope);}), // DIRTY HACK!!! - std::make_pair("Catalog", [&](auto && ) { return make(tree, scope);}), - std::make_pair("ParameterValueDistribution",[&](auto && node) { return make(node, scope);}))) + std::make_pair("Storyboard", [&](auto &&) { return make(tree, scope);}), // DIRTY HACK!!! + std::make_pair("Catalog", [&](auto &&) { return make(tree, scope);}), + std::make_pair("ParameterValueDistribution",[&](auto &&) { return make(tree, scope);}))) // clang-format on { } From 01860c62f6cd810574c10b6e8f972b884f6e94e0 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 21 Feb 2023 17:34:48 +0900 Subject: [PATCH 035/120] refactor(interpreter/ParameterValueDistribution): DeterministicSingleParameterDistributionType --- .../syntax/deterministic_single_parameter_distribution.hpp | 7 +++---- .../syntax/deterministic_single_parameter_distribution.cpp | 5 ++--- 2 files changed, 5 insertions(+), 7 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index 08ccb4cfe1c..3ac7b9c9515 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -33,13 +33,12 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct DeterministicSingleParameterDistribution : public ParameterDistributionContainer +struct DeterministicSingleParameterDistribution +: public DeterministicSingleParameterDistributionType, + public ParameterDistributionContainer { const String parameter_name; - const std::list - deterministic_single_parameter_distributions; - explicit DeterministicSingleParameterDistribution(const pugi::xml_node &, Scope &); auto derive() -> ParameterDistribution override; diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp index 8ee7a912dea..a2af8b43d51 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp @@ -21,9 +21,8 @@ inline namespace syntax { DeterministicSingleParameterDistribution::DeterministicSingleParameterDistribution( const pugi::xml_node & node, Scope & scope) -: parameter_name(readAttribute("parameterName", node, scope)), - deterministic_single_parameter_distributions( - readGroups(node, scope)) +: DeterministicSingleParameterDistributionType(node, scope), + parameter_name(readAttribute("parameterName", node, scope)) { } From d240e51cc428eff801ccb0e456a3668e12511988 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 21 Feb 2023 17:35:04 +0900 Subject: [PATCH 036/120] fix(interpreter/ParameterValueDistribution): DeterministicSingleParameterDistributionType::derive --- ...ministic_single_parameter_distribution.cpp | 26 +++++++------------ 1 file changed, 10 insertions(+), 16 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp index a2af8b43d51..0e8f8b8423f 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp @@ -28,23 +28,17 @@ DeterministicSingleParameterDistribution::DeterministicSingleParameterDistributi ParameterDistribution DeterministicSingleParameterDistribution::derive() { - std::cout << "DeterministicSingleParameterDistribution::derive" << std::endl; ParameterDistribution distribution; - for (auto additional_distribution : deterministic_single_parameter_distributions) { - std::cout << "additional_distribution: " << std::endl; - distribution = mergeParameterDistribution( - distribution, apply( - [this](auto & unnamed_distribution) { - ParameterDistribution distribution; - for (const auto & parameter : unnamed_distribution.derive()) { - distribution.emplace_back(std::make_shared( - ParameterList{{parameter_name, make(parameter)}})); - } - return distribution; - }, - additional_distribution)); - } - return distribution; + return apply( + [&](auto & unnamed_distribution) { + ParameterDistribution distribution; + for (const auto & unnamed_parameter : unnamed_distribution.derive()) { + distribution.emplace_back( + std::make_shared(ParameterList{{parameter_name, unnamed_parameter}})); + } + return distribution; + }, + *this); } } // namespace syntax } // namespace openscenario_interpreter From 9711cae8fc28adb7944ba519ee6b49675f975ab4 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 21 Feb 2023 17:36:00 +0900 Subject: [PATCH 037/120] fix(interpreter/ParameterValueDistribution): replace choice with readGroup in DeterministicParameterDistribution --- .../deterministic_parameter_distribution.cpp | 55 ++++++++++++++++++- 1 file changed, 53 insertions(+), 2 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_parameter_distribution.cpp index 1fa382f686b..728dc0af531 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_parameter_distribution.cpp @@ -19,11 +19,62 @@ namespace openscenario_interpreter { inline namespace syntax { +/** + * Note: + * Most Groups are used only once in one scope of OpenSCENARIO. + * And they can use `choice` function to load the group from the scenario, despite they don't have `xsd:choice` attribute. + * But, DeterministicParameterDistribution group can be used many times in same scope. + * That prevents from using `choice` function. + * Now, we defined new function `readGroup` instead of `choice` + */ +template +auto readGroup(const pugi::xml_node & node, Ts &&... xs) +{ + const std::unordered_map> callees{ + std::forward(xs)...}; + + std::unordered_map specs{}; + + auto print_keys_to = [&](auto & os, const auto & xs) -> decltype(auto) { + if (not xs.empty()) { + for (auto iter = std::begin(xs); iter != std::end(xs); ++iter) { + os << std::get<0>(*iter); + + switch (std::distance(iter, std::end(xs))) { + case 1: + return os; + + case 2: + os << " and "; + break; + + default: + os << ", "; + break; + } + } + } + + return os; + }; + + if (auto callee = callees.find(node.name()); callee != callees.end()) { + return callee->second(node); + } else { + std::stringstream what; + what << "Class " << node.name() << " requires one of following elements: "; + print_keys_to(what, callees); + what << ". But no element specified"; + std::cout << what.str() << std::endl; + throw SyntaxError(what.str()); + } +} + DeterministicParameterDistribution::DeterministicParameterDistribution( - const pugi::xml_node & node, Scope & scope) + const pugi::xml_node & tree, Scope & scope) // clang-format off : Group( - choice(node, + readGroup(tree, std::make_pair("DeterministicMultiParameterDistribution", [&](auto && node){return make(node,scope);}), std::make_pair("DeterministicSingleParameterDistribution", [&](auto && node){return make(node,scope);}))) // clang-format on From a7d1227a3553a75b733686285a3ead8e294c730a Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 21 Feb 2023 17:51:35 +0900 Subject: [PATCH 038/120] fix(interpreter): fix element name --- .../src/syntax/histogram_bin.cpp | 2 +- .../src/syntax/normal_distribution.cpp | 2 +- .../src/syntax/poisson_distribution.cpp | 2 +- .../src/syntax/uniform_distribution.cpp | 2 +- .../src/openscenario_preprocessor.cpp | 38 +++++++++++++------ 5 files changed, 30 insertions(+), 16 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram_bin.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram_bin.cpp index efba445abcf..f11d485b6a2 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram_bin.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram_bin.cpp @@ -20,7 +20,7 @@ namespace openscenario_interpreter inline namespace syntax { HistogramBin::HistogramBin(const pugi::xml_node & node, openscenario_interpreter::Scope & scope) -: range(readElement("range", node, scope)), +: range(readElement("Range", node, scope)), weight(readAttribute("weight", node, scope)) { } diff --git a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp index 16a6654593c..b0cce1d3d5c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp @@ -22,7 +22,7 @@ inline namespace syntax NormalDistribution::NormalDistribution( const pugi::xml_node & node, openscenario_interpreter::Scope & scope) : Scope(scope), - range(readElement("range", node, scope)), + range(readElement("Range", node, scope)), expected_value(readAttribute("expectedValue", node, scope)), variance(readAttribute("variance", node, scope)), distribute(static_cast(expected_value.data), static_cast(variance.data)), diff --git a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp index 1e2a3628b9b..cbbeb717478 100644 --- a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp @@ -22,7 +22,7 @@ inline namespace syntax PoissonDistribution::PoissonDistribution( const pugi::xml_node & node, openscenario_interpreter::Scope & scope) : Scope(scope), - range(readElement("range", node, scope)), + range(readElement("Range", node, scope)), expected_value(readAttribute("expectedValue", node, scope)), distribute(expected_value.data), random_engine(scope.seed) diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index 0caacc91af5..2a4acc6087c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -22,7 +22,7 @@ inline namespace syntax UniformDistribution::UniformDistribution( const pugi::xml_node & node, openscenario_interpreter::Scope & scope) : Scope(scope), - range(readElement("range", node, scope)), + range(readElement("Range", node, scope)), distribute(range.lower_limit.data, range.upper_limit.data), random_engine(scope.seed) { diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp index 5cbbc239b3c..6368e608b71 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include #include #include @@ -81,26 +82,39 @@ void Preprocessor::preprocessScenario(ScenarioSet & scenario) if (validateXOSC(scenario.path)) { if (auto script = std::make_shared(scenario.path); - script->category.is()) { - std::cout << "ParameterValueDistribution!!" << std::endl; - auto base_scenario_path = - script->category.as().scenario_file.filepath; - std::cout << "base_scenario_path : " << base_scenario_path << std::endl; + script->category.is_also()) { + auto & parameter_value_distribution = script->category.as(); + auto base_scenario_path = parameter_value_distribution.scenario_file.filepath; if (boost::filesystem::exists(base_scenario_path)) { if (validateXOSC(base_scenario_path, true)) { - // TODO : implement in feature/parameter_value_distribution branch - // - // parameters = evaluate( parameter_value_distribution( given scenario ) ) - // for( auto derived_scenario : embedParameter( linked scenario, parameters) - // preprocessed_scenarios.emplace_back({derived_scenario, derive_server}); + auto base_scenario = std::make_shared(base_scenario_path); + auto p = parameter_value_distribution.derive(); + for (const auto & parameter_list : p | boost::adaptors::indexed()) { + pugi::xml_document derived_script; + derived_script.reset(base_scenario->script); // deep copy + pugi::xpath_query query("/OpenSCENARIO/ParameterDeclarations"); + auto parameter_declarations = + derived_script.document_element().select_node(query).node(); + for (const auto & [name, parameter] : *parameter_list.value()) { + if (auto parameter_node = + parameter_declarations.find_child_by_attribute("name", name.c_str()); + parameter_node) { + parameter_node.attribute("value").set_value(parameter.as().c_str()); + } else { + std::cout << "Parameter " << name << " not found in base scenario" << std::endl; + } + } + ScenarioSet derived_scenario = scenario; + derived_scenario.path += "." + std::to_string(parameter_list.index()); + derived_script.save_file(derived_scenario.path.c_str()); + preprocessed_scenarios.emplace_back(scenario); + } } else { throw common::Error("base scenario is not valid : " + base_scenario_path.string()); } } else { throw common::Error("base scenario does not exist : " + base_scenario_path.string()); } - std::cout << "base scenario is valid!" << std::endl; - } else { // normal scenario preprocessed_scenarios.emplace_back(scenario); From b03a25582e72f25e9d2e7123ab796105c71ad48e Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 21 Feb 2023 18:18:10 +0900 Subject: [PATCH 039/120] fix(preprocessor): fix output derived scenario --- .../src/openscenario_preprocessor.cpp | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp index 6368e608b71..bd336870cab 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp @@ -85,16 +85,21 @@ void Preprocessor::preprocessScenario(ScenarioSet & scenario) script->category.is_also()) { auto & parameter_value_distribution = script->category.as(); auto base_scenario_path = parameter_value_distribution.scenario_file.filepath; + if (boost::filesystem::exists(base_scenario_path)) { if (validateXOSC(base_scenario_path, true)) { auto base_scenario = std::make_shared(base_scenario_path); auto p = parameter_value_distribution.derive(); + for (const auto & parameter_list : p | boost::adaptors::indexed()) { pugi::xml_document derived_script; derived_script.reset(base_scenario->script); // deep copy - pugi::xpath_query query("/OpenSCENARIO/ParameterDeclarations"); + auto parameter_declarations = - derived_script.document_element().select_node(query).node(); + derived_script.document_element() + .select_node(pugi::xpath_query{"/OpenSCENARIO/ParameterDeclarations"}) + .node(); + for (const auto & [name, parameter] : *parameter_list.value()) { if (auto parameter_node = parameter_declarations.find_child_by_attribute("name", name.c_str()); @@ -104,10 +109,13 @@ void Preprocessor::preprocessScenario(ScenarioSet & scenario) std::cout << "Parameter " << name << " not found in base scenario" << std::endl; } } + ScenarioSet derived_scenario = scenario; derived_scenario.path += "." + std::to_string(parameter_list.index()); + derived_script.save_file(derived_scenario.path.c_str()); - preprocessed_scenarios.emplace_back(scenario); + + preprocessed_scenarios.emplace_back(derived_scenario); } } else { throw common::Error("base scenario is not valid : " + base_scenario_path.string()); From f6426c9936bf6b3384500935f3423eda0b5eff1e Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 21 Feb 2023 18:35:27 +0900 Subject: [PATCH 040/120] refactor(interpreter/ParameterValueDistribution) --- .../openscenario_interpreter/syntax/poisson_distribution.hpp | 1 + .../include/openscenario_interpreter/syntax/range.hpp | 3 ++- .../openscenario_interpreter/src/syntax/deterministic.cpp | 1 + .../src/syntax/distribution_definition.cpp | 4 ++-- .../src/syntax/poisson_distribution.cpp | 1 + .../src/syntax/probability_distribution_set.cpp | 1 + openscenario/openscenario_interpreter/src/syntax/range.cpp | 1 - .../src/syntax/uniform_distribution.cpp | 1 + 8 files changed, 9 insertions(+), 4 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index fa5085543eb..dbf45c664a4 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -48,6 +48,7 @@ struct PoissonDistribution : public ComplexType, std::mt19937 random_engine; explicit PoissonDistribution(const pugi::xml_node &, Scope & scope); + auto derive() -> std::vector override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/range.hpp index 242931bb5d2..6a2eddf8b80 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/range.hpp @@ -34,13 +34,14 @@ inline namespace syntax struct Range { const Double lower_limit = Double::infinity(); + const Double upper_limit = -Double::infinity(); Range() = default; explicit Range(const pugi::xml_node &, Scope &); - [[nodiscard]] auto evaluate(const Double::value_type value) const -> Double::value_type + auto evaluate(const Double::value_type value) const -> Double::value_type { return std::clamp(value, lower_limit.data, upper_limit.data); } diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp index d24c9c069cd..987b3483a83 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp @@ -24,6 +24,7 @@ Deterministic::Deterministic(const pugi::xml_node & node, Scope & scope) readGroups(node, scope)) { } + ParameterDistribution Deterministic::derive() { ParameterDistribution distribution; diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_definition.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_definition.cpp index 705adb01a8a..002386aeedc 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_definition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_definition.cpp @@ -23,8 +23,8 @@ DistributionDefinition::DistributionDefinition(const pugi::xml_node & tree, Scop // clang-format off : Group( choice(tree, - std::make_pair("Deterministic", [&](auto && node){return make(node,scope);}), - std::make_pair("Stochastic", [&](auto && node){return make(node,scope);}))) + std::make_pair("Deterministic", [&](auto && node){return make(node,scope);}), + std::make_pair("Stochastic", [&](auto && node){return make(node,scope);}))) // clang-format on { } diff --git a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp index cbbeb717478..579bde5a10f 100644 --- a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp @@ -28,6 +28,7 @@ PoissonDistribution::PoissonDistribution( random_engine(scope.seed) { } + std::vector PoissonDistribution::derive() { return std::vector({make(distribute(random_engine))}); diff --git a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp index 2a08a97a563..317ce6a3705 100644 --- a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp @@ -36,6 +36,7 @@ ProbabilityDistributionSet::ProbabilityDistributionSet( random_engine(scope.seed) { } + std::vector ProbabilityDistributionSet::derive() { size_t index = distribute(random_engine); diff --git a/openscenario/openscenario_interpreter/src/syntax/range.cpp b/openscenario/openscenario_interpreter/src/syntax/range.cpp index 17a249647de..ec864ed11e5 100644 --- a/openscenario/openscenario_interpreter/src/syntax/range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/range.cpp @@ -24,6 +24,5 @@ Range::Range(const pugi::xml_node & node, Scope & scope) upper_limit(readAttribute("upperLimit", node, scope)) { } - } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index 2a4acc6087c..8018a6eaa24 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -27,6 +27,7 @@ UniformDistribution::UniformDistribution( random_engine(scope.seed) { } + std::vector UniformDistribution::derive() { return std::vector({make(distribute(random_engine))}); From 0035cc58e0212656b5fb04f8807942d182aea9dc Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 21 Feb 2023 18:48:22 +0900 Subject: [PATCH 041/120] doc: update ReleaseNotes --- docs/ReleaseNotes.md | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/docs/ReleaseNotes.md b/docs/ReleaseNotes.md index 8ac8f004d14..705eeea54cb 100644 --- a/docs/ReleaseNotes.md +++ b/docs/ReleaseNotes.md @@ -4,13 +4,14 @@ Major Changes :race_car: :red_car: :blue_car: -| Feature | Brief summary | Category | Pull request | Contributor | -|----------------------------------------------------------------------|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|----------------------------|-----------------------------------------------------------------|-----------------------------------------------| -| Jerk simulation and planning | Start supporting jerk simulation and enable limit jerk while effecting `API::requestSpeedChange` function. | `traffic_simulator` | [#909](https://github.com/tier4/scenario_simulator_v2/pull/909) | [hakuturu583](https://github.com/hakuturu583) | -| OpenSCENARIO 1.2 `SpeedProfileAction` | OpenSCENARIO 1.2 `SpeedProfileAction` is now officially supported. | `openscenario_interpreter` | [#928](https://github.com/tier4/scenario_simulator_v2/pull/928) | [yamacir-kit](https://github.com/yamacir-kit) | -| Randomization of the positions of detected objects | By setting `detectedObjectPositionStandardDeviation` to `ObjectController.Controller.Properties.Property`, it is now possible to add noise to the position of other entities that Autoware recognizes. | `openscenario_interpreter` | [#937](https://github.com/tier4/scenario_simulator_v2/pull/937) | [yamacir-kit](https://github.com/yamacir-kit) | -| `traffic_simulator`'s API `getLateralDistance` | Enable getting lateral distance via `API` class. | `traffic_simulator` | [#945](https://github.com/tier4/scenario_simulator_v2/pull/945) | [hakuturu583](https://github.com/hakuturu583) | -| OpenSCENARIO 1.2 `DistanceCondition` and `RelativeDistanceCondition` | `DistanceCondition` and `RelativeDistanceCondition` now support distance measurement on the lateral axis of the lane coordinate system. | `openscenario_interpreter` | [#962](https://github.com/tier4/scenario_simulator_v2/pull/962) | [yamacir-kit](https://github.com/yamacir-kit) | +| Feature | Brief summary | Category | Pull request | Contributor | +|----------------------------------------------------------------------|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|---------------------------------------------------------|-----------------------------------------------------------------|-----------------------------------------------| +| Jerk simulation and planning | Start supporting jerk simulation and enable limit jerk while effecting `API::requestSpeedChange` function. | `traffic_simulator` | [#909](https://github.com/tier4/scenario_simulator_v2/pull/909) | [hakuturu583](https://github.com/hakuturu583) | +| OpenSCENARIO 1.2 `SpeedProfileAction` | OpenSCENARIO 1.2 `SpeedProfileAction` is now officially supported. | `openscenario_interpreter` | [#928](https://github.com/tier4/scenario_simulator_v2/pull/928) | [yamacir-kit](https://github.com/yamacir-kit) | +| Randomization of the positions of detected objects | By setting `detectedObjectPositionStandardDeviation` to `ObjectController.Controller.Properties.Property`, it is now possible to add noise to the position of other entities that Autoware recognizes. | `openscenario_interpreter` | [#937](https://github.com/tier4/scenario_simulator_v2/pull/937) | [yamacir-kit](https://github.com/yamacir-kit) | +| `traffic_simulator`'s API `getLateralDistance` | Enable getting lateral distance via `API` class. | `traffic_simulator` | [#945](https://github.com/tier4/scenario_simulator_v2/pull/945) | [hakuturu583](https://github.com/hakuturu583) | +| OpenSCENARIO 1.2 `DistanceCondition` and `RelativeDistanceCondition` | `DistanceCondition` and `RelativeDistanceCondition` now support distance measurement on the lateral axis of the lane coordinate system. | `openscenario_interpreter` | [#962](https://github.com/tier4/scenario_simulator_v2/pull/962) | [yamacir-kit](https://github.com/yamacir-kit) | +| OpenSCENARIO 1.2 `ParameterValueDistribution` | Start supporting parameter sweeping using official OpenSCENARIO feature ( it was supported by TIER IV V2 format previously) | `openscenario_interpreter`, `openscenario_preprocessor` | [#878](https://github.com/tier4/scenario_simulator_v2/pull/878) | [HansRobo](https://github.com/HansRobo) | Bug Fixes:bug: From 34b0fbbe97c0914120e9a712d626977c2f4a18e6 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 7 Apr 2023 15:24:05 +0900 Subject: [PATCH 042/120] feat(openscenario_utility): add xml_validator.hpp --- .../openscenario_utility/CMakeLists.txt | 5 ++ .../openscenario_utility/xml_validator.hpp | 82 +++++++++++++++++++ openscenario/openscenario_utility/package.xml | 4 + 3 files changed, 91 insertions(+) create mode 100644 openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp diff --git a/openscenario/openscenario_utility/CMakeLists.txt b/openscenario/openscenario_utility/CMakeLists.txt index 54674273c1a..ea448df0609 100644 --- a/openscenario/openscenario_utility/CMakeLists.txt +++ b/openscenario/openscenario_utility/CMakeLists.txt @@ -7,6 +7,11 @@ find_package(ament_cmake_python REQUIRED) ament_python_install_package(${PROJECT_NAME}) +install( + DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/include/ + DESTINATION include +) + install( DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/${PROJECT_NAME}/ DESTINATION lib/${PROJECT_NAME}) diff --git a/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp b/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp new file mode 100644 index 00000000000..1173302f9c2 --- /dev/null +++ b/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp @@ -0,0 +1,82 @@ +// 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_UTILITY__XML_VALIDATOR_HPP_ +#define OPENSCENARIO_UTILITY__XML_VALIDATOR_HPP_ + +#include +#include +#include +#include +#include +#include +#include + +namespace openscenario_utility +{ +class XMLValidator +{ +public: + explicit XMLValidator(boost::filesystem::path xsd_file = boost::filesystem::path("")) + { + // Initialize Xerces library + xercesc::XMLPlatformUtils::Initialize(); + setXSDFile(xsd_file); + } + + ~XMLValidator() + { + // Terminate Xerces library + xercesc::XMLPlatformUtils::Terminate(); + } + + void setXSDFile(boost::filesystem::path xsd_file) { this->xsd_file = xsd_file; } + + [[nodiscard]] bool validate(const boost::filesystem::path & xml_file) noexcept + { + try { + // Create a DOM parser + xercesc::XercesDOMParser parser; + + // Load the XSD file + parser.loadGrammar(xsd_file.string().c_str(), xercesc::Grammar::SchemaGrammarType, true); + + // Set the validation scheme + xercesc::ErrorHandler * error_handler = new xercesc::HandlerBase(); + parser.setErrorHandler(error_handler); + parser.setValidationScheme(xercesc::XercesDOMParser::Val_Always); + parser.setDoNamespaces(true); + parser.setDoSchema(true); + parser.setValidationConstraintFatal(true); + + // Parse the XML file + parser.parse(xml_file.string().c_str()); + + int error_count = parser.getErrorCount(); + delete error_handler; + return error_count == 0; + + } catch (const xercesc::XMLException & ex) { + std::cerr << "Error: " << ex.getMessage() << std::endl; + return false; + } catch (...) { + std::cerr << "Error: Unknown exception" << std::endl; + return false; + } + } + + boost::filesystem::path xsd_file; +}; +} // namespace openscenario_utility +#endif //OPENSCENARIO_UTILITY__XML_VALIDATOR_HPP_ diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index a4759fdb1bb..14ef860e8b7 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -8,6 +8,10 @@ Apache License 2.0 ament_cmake ament_cmake_python + + rclcpp + xerces + python3-numpy python3-xmlschema python3-yaml From b7e8108a20b36d3c65fa0b69732fc0b6a3942854 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 7 Apr 2023 17:14:26 +0900 Subject: [PATCH 043/120] refactor(openscenario_preprocessor) --- .../openscenario_preprocessor/CMakeLists.txt | 13 ++-- .../openscenario_preprocessor.hpp | 41 ++++------- .../openscenario_preprocessor/package.xml | 39 +++++----- .../src/openscenario_preprocessor.cpp | 61 +--------------- .../src/openscenario_preprocessor_node.cpp | 72 +++++++++++++++++-- .../openscenario_utility/CMakeLists.txt | 9 +-- 6 files changed, 115 insertions(+), 120 deletions(-) diff --git a/openscenario/openscenario_preprocessor/CMakeLists.txt b/openscenario/openscenario_preprocessor/CMakeLists.txt index a910a63014f..76d716ceb20 100644 --- a/openscenario/openscenario_preprocessor/CMakeLists.txt +++ b/openscenario/openscenario_preprocessor/CMakeLists.txt @@ -11,15 +11,18 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") endif() find_package(ament_cmake_auto REQUIRED) - +find_package(PkgConfig REQUIRED) +pkg_check_modules(XcercesC xerces-c) ament_auto_find_build_dependencies() -ament_auto_add_library(${PROJECT_NAME} SHARED src/${PROJECT_NAME}.cpp) - -target_link_libraries(${PROJECT_NAME} glog) +# global includes +include_directories(${XcercesC_INCLUDE_DIRS}) -rclcpp_components_register_nodes(${PROJECT_NAME} "openscenario_preprocessor::Preprocessor") +# common shared library +ament_auto_add_library(${PROJECT_NAME} SHARED src/${PROJECT_NAME}.cpp) +target_link_libraries(${PROJECT_NAME} ${XcercesC_LIBRARIES}) +# node ament_auto_add_executable(${PROJECT_NAME}_node src/${PROJECT_NAME}_node.cpp) target_link_libraries(${PROJECT_NAME}_node ${PROJECT_NAME}) diff --git a/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp b/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp index 2ce18623270..23e3703ad09 100644 --- a/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp +++ b/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp @@ -15,14 +15,10 @@ #ifndef OPENSCENARIO_PREPROCESSOR__OPENSCENARIO_PREPROCESSOR_HPP_ #define OPENSCENARIO_PREPROCESSOR__OPENSCENARIO_PREPROCESSOR_HPP_ -#include #include #include #include -#include -#include -#include -#include +#include namespace openscenario_preprocessor { @@ -30,20 +26,9 @@ struct ScenarioSet { ScenarioSet() = default; - explicit ScenarioSet(openscenario_preprocessor_msgs::srv::Load::Request & load_request) + explicit ScenarioSet(std::string path, int expect, float frame_rate) + : path(path), expect(expect), frame_rate(frame_rate) { - path = load_request.path; - expect = load_request.expect; - frame_rate = load_request.frame_rate; - } - - auto getDeriveResponse() -> openscenario_preprocessor_msgs::srv::Derive::Response - { - openscenario_preprocessor_msgs::srv::Derive::Response response; - response.path = path; - response.expect = expect; - response.frame_rate = frame_rate; - return response; } std::string path; @@ -53,27 +38,25 @@ struct ScenarioSet float frame_rate; }; -class Preprocessor : public rclcpp::Node +class Preprocessor { public: - explicit Preprocessor(const rclcpp::NodeOptions &); + explicit Preprocessor() : xml_validator("") {} -private: +protected: void preprocessScenario(ScenarioSet &); - [[nodiscard]] bool validateXOSC(const boost::filesystem::path &, bool); - - rclcpp::Service::SharedPtr load_server; - - rclcpp::Service::SharedPtr derive_server; - - rclcpp::Service::SharedPtr - check_server; + [[nodiscard]] bool validateXOSC( + const boost::filesystem::path & target_file, const boost::filesystem::path & xsd_file, + bool verbose = false); std::deque preprocessed_scenarios; std::mutex preprocessed_scenarios_mutex; + + openscenario_utility::XMLValidator xml_validator; }; + } // namespace openscenario_preprocessor #endif // OPENSCENARIO_PREPROCESSOR__OPENSCENARIO_PREPROCESSOR_HPP_ diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 89c112f2cfd..1a1ec2ed6d9 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -2,27 +2,28 @@ - openscenario_preprocessor - 0.6.7 - Example package for TIER IV OpenSCENARIO Interpreter - Kotaro Yoshimoto - Apache License 2.0 + openscenario_preprocessor + 0.6.7 + Example package for TIER IV OpenSCENARIO Interpreter + Kotaro Yoshimoto + Apache License 2.0 - ament_cmake_auto + ament_cmake_auto - libgoogle-glog-dev - openscenario_interpreter - openscenario_preprocessor_msgs - rclcpp + libgoogle-glog-dev + openscenario_interpreter + openscenario_preprocessor_msgs + rclcpp + openscenario_utility - ament_cmake_clang_format - ament_cmake_copyright - ament_cmake_gtest - ament_cmake_pep257 - ament_cmake_xmllint - ament_lint_auto + ament_cmake_clang_format + ament_cmake_copyright + ament_cmake_gtest + ament_cmake_pep257 + ament_cmake_xmllint + ament_lint_auto - - ament_cmake - + + ament_cmake + diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp index bd336870cab..ca31d94fb22 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp @@ -17,77 +17,22 @@ #include #include #include -#include namespace openscenario_preprocessor { -Preprocessor::Preprocessor(const rclcpp::NodeOptions & options) -: rclcpp::Node("preprocessor", options), - load_server(create_service( - "~/load", - [this]( - const openscenario_preprocessor_msgs::srv::Load::Request::SharedPtr request, - openscenario_preprocessor_msgs::srv::Load::Response::SharedPtr response) -> void { - auto lock = std::lock_guard(preprocessed_scenarios_mutex); - try { - auto s = ScenarioSet(*request); - preprocessScenario(s); - response->has_succeeded = true; - response->message = "success"; - } catch (std::exception & e) { - response->has_succeeded = false; - response->message = e.what(); - preprocessed_scenarios.clear(); - } - })), - derive_server(create_service( - "~/derive", - [this]( - const openscenario_preprocessor_msgs::srv::Derive::Request::SharedPtr, - openscenario_preprocessor_msgs::srv::Derive::Response::SharedPtr response) -> void { - auto lock = std::lock_guard(preprocessed_scenarios_mutex); - if (preprocessed_scenarios.empty()) { - response->path = "no output"; - } else { - *response = preprocessed_scenarios.front().getDeriveResponse(); - preprocessed_scenarios.pop_front(); - } - })), - check_server(create_service( - "~/check", - [this]( - const openscenario_preprocessor_msgs::srv::CheckDerivativeRemained::Request::SharedPtr, - openscenario_preprocessor_msgs::srv::CheckDerivativeRemained::Response::SharedPtr response) - -> void { - auto lock = std::lock_guard(preprocessed_scenarios_mutex); - response->derivative_remained = not preprocessed_scenarios.empty(); - })) -{ -} - -bool Preprocessor::validateXOSC(const boost::filesystem::path & file_name, bool verbose = false) -{ - auto result = - concealer::dollar("ros2 run openscenario_utility validation.py " + file_name.string()); - if (verbose) { - std::cout << "validate : " << result << std::endl; - } - return result.find("All xosc files given are standard compliant.") != std::string::npos; -} - void Preprocessor::preprocessScenario(ScenarioSet & scenario) { using openscenario_interpreter::OpenScenario; using openscenario_interpreter::ParameterValueDistribution; - if (validateXOSC(scenario.path)) { + if (xml_validator.validate(scenario.path)) { if (auto script = std::make_shared(scenario.path); script->category.is_also()) { auto & parameter_value_distribution = script->category.as(); auto base_scenario_path = parameter_value_distribution.scenario_file.filepath; if (boost::filesystem::exists(base_scenario_path)) { - if (validateXOSC(base_scenario_path, true)) { + if (xml_validator.validate(base_scenario_path)) { auto base_scenario = std::make_shared(base_scenario_path); auto p = parameter_value_distribution.derive(); @@ -132,5 +77,3 @@ void Preprocessor::preprocessScenario(ScenarioSet & scenario) } } } // namespace openscenario_preprocessor - -RCLCPP_COMPONENTS_REGISTER_NODE(openscenario_preprocessor::Preprocessor) diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp index b85e871aab4..0b5f355cc94 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp @@ -12,16 +12,80 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +//#include #include #include #include +#include +#include +#include +#include + +class PreprocessorNode : public rclcpp::Node, public openscenario_preprocessor::Preprocessor +{ +public: + explicit PreprocessorNode(const rclcpp::NodeOptions & options) + : rclcpp::Node("preprocessor", options), + openscenario_preprocessor::Preprocessor(), + load_server(create_service( + "~/load", + [this]( + const openscenario_preprocessor_msgs::srv::Load::Request::SharedPtr request, + openscenario_preprocessor_msgs::srv::Load::Response::SharedPtr response) -> void { + auto lock = std::lock_guard(preprocessed_scenarios_mutex); + try { + auto s = openscenario_preprocessor::ScenarioSet( + request->path, request->expect, request->frame_rate); + preprocessScenario(s); + response->has_succeeded = true; + response->message = "success"; + } catch (std::exception & e) { + response->has_succeeded = false; + response->message = e.what(); + preprocessed_scenarios.clear(); + } + })), + derive_server(create_service( + "~/derive", + [this]( + const openscenario_preprocessor_msgs::srv::Derive::Request::SharedPtr, + openscenario_preprocessor_msgs::srv::Derive::Response::SharedPtr response) -> void { + auto lock = std::lock_guard(preprocessed_scenarios_mutex); + if (preprocessed_scenarios.empty()) { + response->path = "no output"; + } else { + response->path = preprocessed_scenarios.front().path; + response->expect = preprocessed_scenarios.front().expect; + response->frame_rate = preprocessed_scenarios.front().frame_rate; + preprocessed_scenarios.pop_front(); + } + })), + check_server(create_service( + "~/check", + [this]( + const openscenario_preprocessor_msgs::srv::CheckDerivativeRemained::Request::SharedPtr, + openscenario_preprocessor_msgs::srv::CheckDerivativeRemained::Response::SharedPtr response) + -> void { + auto lock = std::lock_guard(preprocessed_scenarios_mutex); + response->derivative_remained = not preprocessed_scenarios.empty(); + })) + { + } + +private: + rclcpp::Service::SharedPtr load_server; + + rclcpp::Service::SharedPtr derive_server; + + rclcpp::Service::SharedPtr + check_server; +}; int main(const int argc, char const * const * const argv) { - google::InitGoogleLogging(argv[0]); - google::InstallFailureSignalHandler(); + // google::InitGoogleLogging(argv[0]); + // google::InstallFailureSignalHandler(); rclcpp::init(argc, argv); @@ -29,7 +93,7 @@ int main(const int argc, char const * const * const argv) rclcpp::NodeOptions options{}; - auto node = std::make_shared(options); + auto node = std::make_shared(options); executor.add_node((*node).get_node_base_interface()); diff --git a/openscenario/openscenario_utility/CMakeLists.txt b/openscenario/openscenario_utility/CMakeLists.txt index ea448df0609..c9cd12dedaf 100644 --- a/openscenario/openscenario_utility/CMakeLists.txt +++ b/openscenario/openscenario_utility/CMakeLists.txt @@ -7,13 +7,14 @@ find_package(ament_cmake_python REQUIRED) ament_python_install_package(${PROJECT_NAME}) +install( + DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/${PROJECT_NAME}/ + DESTINATION lib/${PROJECT_NAME}) + install( DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/include/ DESTINATION include ) - -install( - DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/${PROJECT_NAME}/ - DESTINATION lib/${PROJECT_NAME}) +ament_export_include_directories(include) ament_package() From 17e12e0fad045c4a56f3ce7d37c4be7d0405ccc2 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 7 Apr 2023 17:32:22 +0900 Subject: [PATCH 044/120] chore(cspell): add "xerces" to dictionary --- .github/workflows/custom_spell.json | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/.github/workflows/custom_spell.json b/.github/workflows/custom_spell.json index 799e0de4c78..8c47782c42b 100644 --- a/.github/workflows/custom_spell.json +++ b/.github/workflows/custom_spell.json @@ -27,6 +27,8 @@ "randomizers", "subspline", "TESTRANDOMIZER", - "travelling" + "travelling", + "xerces", + "xercesc" ] } From 3f149d772514faa72376a7fdccc853f211e1709e Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 7 Apr 2023 17:34:18 +0900 Subject: [PATCH 045/120] chore(cspell): fix typo --- openscenario/openscenario_preprocessor/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/openscenario/openscenario_preprocessor/CMakeLists.txt b/openscenario/openscenario_preprocessor/CMakeLists.txt index 76d716ceb20..f1ffba21828 100644 --- a/openscenario/openscenario_preprocessor/CMakeLists.txt +++ b/openscenario/openscenario_preprocessor/CMakeLists.txt @@ -12,15 +12,15 @@ endif() find_package(ament_cmake_auto REQUIRED) find_package(PkgConfig REQUIRED) -pkg_check_modules(XcercesC xerces-c) +pkg_check_modules(XercesC xerces-c) ament_auto_find_build_dependencies() # global includes -include_directories(${XcercesC_INCLUDE_DIRS}) +include_directories(${XercesC_INCLUDE_DIRS}) # common shared library ament_auto_add_library(${PROJECT_NAME} SHARED src/${PROJECT_NAME}.cpp) -target_link_libraries(${PROJECT_NAME} ${XcercesC_LIBRARIES}) +target_link_libraries(${PROJECT_NAME} ${XercesC_LIBRARIES}) # node ament_auto_add_executable(${PROJECT_NAME}_node src/${PROJECT_NAME}_node.cpp) From 80505e45768dc59be00cf72bbbfc88dd25198d29 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 7 Apr 2023 18:21:10 +0900 Subject: [PATCH 046/120] doc(scenario_test_runner): add sample scenarios --- .../Deterministic.DistributionRange.xosc | 15 ++ .../Deterministic.DistributionSet.xosc | 17 ++ .../Deterministic.ValueSetDistribution.xosc | 18 +++ .../scenario/Stochastic.Histogram.xosc | 23 +++ .../Stochastic.NormalDistribution.xosc | 15 ++ .../Stochastic.PoissonDistribution.xosc | 15 ++ ...Stochastic.ProbabilityDistributionSet.xosc | 17 ++ .../Stochastic.UniformDistribution.xosc | 15 ++ .../scenario_test_runner/scenario/sample.xosc | 146 ++++++++++++++++++ 9 files changed, 281 insertions(+) create mode 100644 test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc create mode 100644 test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc create mode 100644 test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc create mode 100644 test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc create mode 100644 test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc create mode 100644 test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc create mode 100644 test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc create mode 100644 test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc create mode 100644 test_runner/scenario_test_runner/scenario/sample.xosc diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc new file mode 100644 index 00000000000..43eb2b46b67 --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc new file mode 100644 index 00000000000..40a0c528f31 --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc b/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc new file mode 100644 index 00000000000..9de672c647c --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc new file mode 100644 index 00000000000..e412a225fe8 --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc new file mode 100644 index 00000000000..a711981784d --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc new file mode 100644 index 00000000000..128e996affe --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc new file mode 100644 index 00000000000..eeb9212d9c3 --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc new file mode 100644 index 00000000000..9440d3ca902 --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/test_runner/scenario_test_runner/scenario/sample.xosc b/test_runner/scenario_test_runner/scenario/sample.xosc new file mode 100644 index 00000000000..d8933818459 --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/sample.xosc @@ -0,0 +1,146 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 4e11164a7d733e632d8f8e2a184d3723074d939c Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 7 Apr 2023 18:36:13 +0900 Subject: [PATCH 047/120] chore(scenario_test_runner): update sample scenarios --- .../scenario/Deterministic.DistributionRange.xosc | 5 ++--- .../scenario/Deterministic.DistributionSet.xosc | 5 ++--- .../scenario/Deterministic.ValueSetDistribution.xosc | 5 ++--- .../scenario_test_runner/scenario/Stochastic.Histogram.xosc | 5 ++--- .../scenario/Stochastic.NormalDistribution.xosc | 5 ++--- .../scenario/Stochastic.PoissonDistribution.xosc | 5 ++--- .../scenario/Stochastic.ProbabilityDistributionSet.xosc | 5 ++--- .../scenario/Stochastic.UniformDistribution.xosc | 5 ++--- 8 files changed, 16 insertions(+), 24 deletions(-) diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc index 43eb2b46b67..c5487edf7c6 100644 --- a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc +++ b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc @@ -1,9 +1,8 @@ - - + @@ -12,4 +11,4 @@ - \ No newline at end of file + diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc index 40a0c528f31..83773ea7c02 100644 --- a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc +++ b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc @@ -1,9 +1,8 @@ - - + @@ -14,4 +13,4 @@ - \ No newline at end of file + diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc b/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc index 9de672c647c..20933b651b6 100644 --- a/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc +++ b/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc @@ -1,9 +1,8 @@ - - + @@ -15,4 +14,4 @@ - \ No newline at end of file + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc index e412a225fe8..ec43a3c1b99 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc +++ b/test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc @@ -1,9 +1,8 @@ - - + @@ -20,4 +19,4 @@ - \ No newline at end of file + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc index a711981784d..5019af40009 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc +++ b/test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc @@ -1,9 +1,8 @@ - - + @@ -12,4 +11,4 @@ - \ No newline at end of file + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc index 128e996affe..53425f219bb 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc +++ b/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc @@ -1,9 +1,8 @@ - - + @@ -12,4 +11,4 @@ - \ No newline at end of file + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc index eeb9212d9c3..db4329da7f2 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc +++ b/test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc @@ -1,9 +1,8 @@ - - + @@ -14,4 +13,4 @@ - \ No newline at end of file + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc index 9440d3ca902..70ef6d7a9db 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc +++ b/test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc @@ -1,9 +1,8 @@ - - + @@ -12,4 +11,4 @@ - \ No newline at end of file + From d0f7acf22d01ef1dcb45d90c5e5af4936de56b29 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 10 Apr 2023 17:49:32 +0900 Subject: [PATCH 048/120] chore(openscenario_preprocessor): fix xsd_path option --- .../src/openscenario_preprocessor_node.cpp | 8 ++++++-- openscenario/openscenario_utility/CMakeLists.txt | 1 + .../include/openscenario_utility/xml_validator.hpp | 7 ++----- 3 files changed, 9 insertions(+), 7 deletions(-) diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp index 0b5f355cc94..4a8e466400c 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp @@ -14,6 +14,7 @@ //#include +#include #include #include #include @@ -25,7 +26,7 @@ class PreprocessorNode : public rclcpp::Node, public openscenario_preprocessor::Preprocessor { public: - explicit PreprocessorNode(const rclcpp::NodeOptions & options) + explicit PreprocessorNode(const rclcpp::NodeOptions & options, const std::string xsd_path) : rclcpp::Node("preprocessor", options), openscenario_preprocessor::Preprocessor(), load_server(create_service( @@ -93,7 +94,10 @@ int main(const int argc, char const * const * const argv) rclcpp::NodeOptions options{}; - auto node = std::make_shared(options); + std::string xsd_path = ament_index_cpp::get_package_share_directory("openscenario_utility") + + "/../lib/openscenario_utility/resources/OpenSCENARIO-1.2.xsd"; + + auto node = std::make_shared(options, xsd_path); executor.add_node((*node).get_node_base_interface()); diff --git a/openscenario/openscenario_utility/CMakeLists.txt b/openscenario/openscenario_utility/CMakeLists.txt index c9cd12dedaf..2829634aaf6 100644 --- a/openscenario/openscenario_utility/CMakeLists.txt +++ b/openscenario/openscenario_utility/CMakeLists.txt @@ -15,6 +15,7 @@ install( DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/include/ DESTINATION include ) + ament_export_include_directories(include) ament_package() diff --git a/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp b/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp index 1173302f9c2..a04e2fb2e60 100644 --- a/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp +++ b/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp @@ -28,11 +28,10 @@ namespace openscenario_utility class XMLValidator { public: - explicit XMLValidator(boost::filesystem::path xsd_file = boost::filesystem::path("")) + explicit XMLValidator(boost::filesystem::path xsd_file) : xsd_file(xsd_file) { // Initialize Xerces library xercesc::XMLPlatformUtils::Initialize(); - setXSDFile(xsd_file); } ~XMLValidator() @@ -41,7 +40,6 @@ class XMLValidator xercesc::XMLPlatformUtils::Terminate(); } - void setXSDFile(boost::filesystem::path xsd_file) { this->xsd_file = xsd_file; } [[nodiscard]] bool validate(const boost::filesystem::path & xml_file) noexcept { @@ -55,7 +53,7 @@ class XMLValidator // Set the validation scheme xercesc::ErrorHandler * error_handler = new xercesc::HandlerBase(); parser.setErrorHandler(error_handler); - parser.setValidationScheme(xercesc::XercesDOMParser::Val_Always); + parser.setValidationScheme(xercesc::XercesDOMParser::Val_Auto); parser.setDoNamespaces(true); parser.setDoSchema(true); parser.setValidationConstraintFatal(true); @@ -66,7 +64,6 @@ class XMLValidator int error_count = parser.getErrorCount(); delete error_handler; return error_count == 0; - } catch (const xercesc::XMLException & ex) { std::cerr << "Error: " << ex.getMessage() << std::endl; return false; From a2081355497f235ad0c82b950f11e04e7f676c6c Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 10 Apr 2023 17:51:01 +0900 Subject: [PATCH 049/120] feat(openscenario_preprocessor): add output_directory option --- .../openscenario_preprocessor.hpp | 7 ++++++- .../src/openscenario_preprocessor.cpp | 12 +++++++++++- .../src/openscenario_preprocessor_node.cpp | 5 ++++- 3 files changed, 21 insertions(+), 3 deletions(-) diff --git a/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp b/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp index 23e3703ad09..6b5ca3b836f 100644 --- a/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp +++ b/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp @@ -41,7 +41,10 @@ struct ScenarioSet class Preprocessor { public: - explicit Preprocessor() : xml_validator("") {} + explicit Preprocessor(boost::filesystem::path xsd_path, boost::filesystem::path output_directory) + : xml_validator(xsd_path), output_directory(output_directory) + { + } protected: void preprocessScenario(ScenarioSet &); @@ -55,6 +58,8 @@ class Preprocessor std::mutex preprocessed_scenarios_mutex; openscenario_utility::XMLValidator xml_validator; + + boost::filesystem::path output_directory; }; } // namespace openscenario_preprocessor diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp index ca31d94fb22..4d5e4f27770 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp @@ -56,8 +56,18 @@ void Preprocessor::preprocessScenario(ScenarioSet & scenario) } ScenarioSet derived_scenario = scenario; - derived_scenario.path += "." + std::to_string(parameter_list.index()); + boost::filesystem::path derived_scenario_path(derived_scenario.path); + derived_scenario_path = output_directory / derived_scenario_path.filename(); + derived_scenario_path.replace_extension( + derived_scenario_path.extension().string() + "." + + std::to_string(parameter_list.index())); + + derived_scenario.path = derived_scenario_path.string(); + + if (not boost::filesystem::exists(output_directory)) { + boost::filesystem::create_directories(output_directory); + } derived_script.save_file(derived_scenario.path.c_str()); preprocessed_scenarios.emplace_back(derived_scenario); diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp index 4a8e466400c..c95d4f28335 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp @@ -28,7 +28,10 @@ class PreprocessorNode : public rclcpp::Node, public openscenario_preprocessor:: public: explicit PreprocessorNode(const rclcpp::NodeOptions & options, const std::string xsd_path) : rclcpp::Node("preprocessor", options), - openscenario_preprocessor::Preprocessor(), + openscenario_preprocessor::Preprocessor(xsd_path, [this]{ + declare_parameter("output_directory", "/tmp/openscenario_preprocessor"); + return get_parameter("output_directory").as_string(); + }()), load_server(create_service( "~/load", [this]( From 789c34543a229cd1c189df158dbd5782d0925be5 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 10 Apr 2023 17:51:38 +0900 Subject: [PATCH 050/120] fix(openscenario_interpreter): fix ParameterValueSet::evaluate() --- .../src/syntax/parameter_value_set.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp b/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp index 642cb21bb05..e3538eaa0ec 100644 --- a/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/parameter_value_set.cpp @@ -28,9 +28,10 @@ ParameterValueSet::ParameterValueSet( auto ParameterValueSet::evaluate() const -> std::shared_ptr> { - std::shared_ptr> parameters; + std::shared_ptr> parameters = + std::make_shared>(); for (const auto & parameter : parameter_assignments) { - parameters->at(parameter.parameterRef) = make(parameter.value); + (*parameters)[parameter.parameterRef] = make(parameter.value); } return parameters; } From 998560c7c97ffd82532624d6f6008b42f5ce4500 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 10 Apr 2023 19:13:51 +0900 Subject: [PATCH 051/120] update scenarios --- .../scenario/Deterministic.DistributionSet.xosc | 2 +- .../scenario/Deterministic.ValueSetDistribution.xosc | 3 +-- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc index 83773ea7c02..9ed2c9244cf 100644 --- a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc +++ b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc @@ -1,6 +1,6 @@ - + diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc b/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc index 20933b651b6..f81017b9d3b 100644 --- a/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc +++ b/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc @@ -1,4 +1,3 @@ - @@ -7,7 +6,7 @@ - + From c80a6b802a5abd081a4f66871907d24b091a49e7 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 10 Apr 2023 19:58:48 +0900 Subject: [PATCH 052/120] update scenarios --- .../scenario/Stochastic.PoissonDistribution.xosc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc index 53425f219bb..a47f9f546ad 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc +++ b/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc @@ -5,7 +5,7 @@ - + From 59c9868a391d21616e811f13c80929c986ff36eb Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 10 Apr 2023 20:10:16 +0900 Subject: [PATCH 053/120] fix(openscenario_preprocessor): share random_engine --- .../include/openscenario_interpreter/scope.hpp | 4 +++- .../include/openscenario_interpreter/syntax/histogram.hpp | 4 +--- .../syntax/normal_distribution.hpp | 4 +--- .../syntax/poisson_distribution.hpp | 4 +--- .../syntax/probability_distribution_set.hpp | 4 +--- .../syntax/uniform_distribution.hpp | 4 +--- .../syntax/user_defined_distribution.hpp | 2 +- .../openscenario_interpreter/src/syntax/histogram.cpp | 3 +-- .../src/syntax/normal_distribution.cpp | 3 +-- .../src/syntax/poisson_distribution.cpp | 5 ++--- .../src/syntax/probability_distribution_set.cpp | 3 +-- .../openscenario_interpreter/src/syntax/stochastic.cpp | 7 +++++-- .../src/syntax/uniform_distribution.cpp | 3 +-- 13 files changed, 20 insertions(+), 30 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/scope.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/scope.hpp index 4a2ebd26c49..1f5a8ba8968 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/scope.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/scope.hpp @@ -24,6 +24,7 @@ #include #include #include +#include #include #include #include @@ -192,7 +193,8 @@ class Scope std::list actors; - double seed; // NOTE: `seed` is used only for sharing randomSeed in Stochastic now + // NOTE: `random_engine` is used only for sharing random number generator in Stochastic now + std::mt19937 random_engine; Scope() = delete; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index a291cb438e2..b1f8bb50b9c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -34,7 +34,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ -struct Histogram : public ComplexType, private Scope, public SingleParameterDistributionBase +struct Histogram : public ComplexType, protected Scope, public SingleParameterDistributionBase { /** * Note: HistogramBin must be stored in continuous range and ascending order to `bins` @@ -58,8 +58,6 @@ struct Histogram : public ComplexType, private Scope, public SingleParameterDist std::piecewise_constant_distribution distribute; - std::mt19937 random_engine; - explicit Histogram(const pugi::xml_node &, Scope & scope); auto derive() -> std::vector override; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp index d5395cac07e..576979ad6eb 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp @@ -39,7 +39,7 @@ inline namespace syntax * -------------------------------------------------------------------------- */ struct NormalDistribution : public ComplexType, - private Scope, + protected Scope, public SingleParameterDistributionBase { const Range range; @@ -50,8 +50,6 @@ struct NormalDistribution : public ComplexType, std::normal_distribution distribute; - std::mt19937 random_engine; - explicit NormalDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> std::vector override; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index dbf45c664a4..b0768013229 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -36,7 +36,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ struct PoissonDistribution : public ComplexType, - private Scope, + protected Scope, public SingleParameterDistributionBase { const Range range; @@ -45,8 +45,6 @@ struct PoissonDistribution : public ComplexType, std::poisson_distribution<> distribute; - std::mt19937 random_engine; - explicit PoissonDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> std::vector override; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index dd81bbc658d..82f3488c5c2 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -34,7 +34,7 @@ inline namespace syntax * -------------------------------------------------------------------------- */ struct ProbabilityDistributionSet : public ComplexType, - private Scope, + protected Scope, public SingleParameterDistributionBase { const std::vector elements; @@ -55,8 +55,6 @@ struct ProbabilityDistributionSet : public ComplexType, std::discrete_distribution distribute; - std::mt19937 random_engine; - explicit ProbabilityDistributionSet(const pugi::xml_node &, Scope & scope); auto derive() -> std::vector override; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index dd4ca7b33cc..81831d1f5a5 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -34,15 +34,13 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ struct UniformDistribution : public ComplexType, - private Scope, + protected Scope, public SingleParameterDistributionBase { const Range range; std::uniform_real_distribution distribute; - std::mt19937 random_engine; - explicit UniformDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> std::vector override; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp index 6f8d552cfbd..fe6ede458ea 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp @@ -33,7 +33,7 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct UserDefinedDistribution : private Scope, public ComplexType +struct UserDefinedDistribution : protected Scope, public ComplexType { const String type; diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp index 3c22f148e1b..9325d2073a7 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp @@ -24,8 +24,7 @@ Histogram::Histogram(const pugi::xml_node & node, openscenario_interpreter::Scop bins(readElements("Bin", node, scope)), bin_adaptor(bins), distribute( - bin_adaptor.intervals.begin(), bin_adaptor.intervals.end(), bin_adaptor.densities.begin()), - random_engine(scope.seed) + bin_adaptor.intervals.begin(), bin_adaptor.intervals.end(), bin_adaptor.densities.begin()) { } diff --git a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp index b0cce1d3d5c..0fd89ba066c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp @@ -25,8 +25,7 @@ NormalDistribution::NormalDistribution( range(readElement("Range", node, scope)), expected_value(readAttribute("expectedValue", node, scope)), variance(readAttribute("variance", node, scope)), - distribute(static_cast(expected_value.data), static_cast(variance.data)), - random_engine(scope.seed) + distribute(static_cast(expected_value.data), static_cast(variance.data)) { } std::vector NormalDistribution::derive() diff --git a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp index 579bde5a10f..3597072385d 100644 --- a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp @@ -24,14 +24,13 @@ PoissonDistribution::PoissonDistribution( : Scope(scope), range(readElement("Range", node, scope)), expected_value(readAttribute("expectedValue", node, scope)), - distribute(expected_value.data), - random_engine(scope.seed) + distribute(expected_value.data) { } std::vector PoissonDistribution::derive() { - return std::vector({make(distribute(random_engine))}); + return std::vector({make(range.evaluate(distribute(random_engine)))}); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp index 317ce6a3705..a4f9d888214 100644 --- a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp @@ -32,8 +32,7 @@ ProbabilityDistributionSet::ProbabilityDistributionSet( elements( generateVector(readElements("Element", node, scope))), adaptor(elements), - distribute(adaptor.probabilities.begin(), adaptor.probabilities.end()), - random_engine(scope.seed) + distribute(adaptor.probabilities.begin(), adaptor.probabilities.end()) { } diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp index 8b7c95c9dae..15df998b6f0 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp @@ -26,8 +26,11 @@ inline namespace syntax */ Stochastic::Stochastic(const pugi::xml_node & node, Scope & scope) : number_of_test_runs(readAttribute("numberOfTestRuns", node, scope)), - random_seed( - scope.seed = static_cast(readAttribute("randomSeed", node, scope, 0))), + random_seed([&] { + auto seed = static_cast(readAttribute("randomSeed", node, scope, 0)); + scope.random_engine.seed(seed); + return seed; + }()), stochastic_distribution( readElement("StochasticDistribution", node, scope)) { diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index 8018a6eaa24..28ac8ba44c4 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -23,8 +23,7 @@ UniformDistribution::UniformDistribution( const pugi::xml_node & node, openscenario_interpreter::Scope & scope) : Scope(scope), range(readElement("Range", node, scope)), - distribute(range.lower_limit.data, range.upper_limit.data), - random_engine(scope.seed) + distribute(range.lower_limit.data, range.upper_limit.data) { } From 43f0d11fe61e8deb3587189688bb4137030f4ec8 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 10 Apr 2023 20:11:04 +0900 Subject: [PATCH 054/120] fix(openscenario_preprocessor): convert parameters into std::string --- .../src/openscenario_preprocessor.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp index 4d5e4f27770..76391ad5322 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp @@ -49,7 +49,9 @@ void Preprocessor::preprocessScenario(ScenarioSet & scenario) if (auto parameter_node = parameter_declarations.find_child_by_attribute("name", name.c_str()); parameter_node) { - parameter_node.attribute("value").set_value(parameter.as().c_str()); + std::stringstream parameter_stringstream; + parameter_stringstream << value; + parameter_node.attribute("value").set_value(parameter_stringstream.str().c_str()); } else { std::cout << "Parameter " << name << " not found in base scenario" << std::endl; } @@ -57,6 +59,7 @@ void Preprocessor::preprocessScenario(ScenarioSet & scenario) ScenarioSet derived_scenario = scenario; + // generate new scenario file name boost::filesystem::path derived_scenario_path(derived_scenario.path); derived_scenario_path = output_directory / derived_scenario_path.filename(); derived_scenario_path.replace_extension( From ad9975f70c42114f322ed9d96077cf2bfae5701f Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 10 Apr 2023 20:12:44 +0900 Subject: [PATCH 055/120] chore: apply linter --- .../src/openscenario_preprocessor_node.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp index c95d4f28335..66e05b54cfb 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp @@ -28,10 +28,12 @@ class PreprocessorNode : public rclcpp::Node, public openscenario_preprocessor:: public: explicit PreprocessorNode(const rclcpp::NodeOptions & options, const std::string xsd_path) : rclcpp::Node("preprocessor", options), - openscenario_preprocessor::Preprocessor(xsd_path, [this]{ - declare_parameter("output_directory", "/tmp/openscenario_preprocessor"); + openscenario_preprocessor::Preprocessor( + xsd_path, + [this] { + declare_parameter("output_directory", "/tmp/openscenario_preprocessor"); return get_parameter("output_directory").as_string(); - }()), + }()), load_server(create_service( "~/load", [this]( From 0787ef35d4c324f59413e9118c66948c6cd339a2 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 11 Apr 2023 10:50:52 +0900 Subject: [PATCH 056/120] refactor(openscenario_preprocessor): fix inheritance access keywords --- .../openscenario_interpreter/syntax/normal_distribution.hpp | 2 +- .../openscenario_interpreter/syntax/poisson_distribution.hpp | 2 +- .../syntax/probability_distribution_set.hpp | 2 +- .../openscenario_interpreter/syntax/uniform_distribution.hpp | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp index 576979ad6eb..aacf1078447 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp @@ -39,7 +39,7 @@ inline namespace syntax * -------------------------------------------------------------------------- */ struct NormalDistribution : public ComplexType, - protected Scope, + private Scope, public SingleParameterDistributionBase { const Range range; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index b0768013229..9cfbf59db3d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -36,7 +36,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ struct PoissonDistribution : public ComplexType, - protected Scope, + private Scope, public SingleParameterDistributionBase { const Range range; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index 82f3488c5c2..09481874137 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -34,7 +34,7 @@ inline namespace syntax * -------------------------------------------------------------------------- */ struct ProbabilityDistributionSet : public ComplexType, - protected Scope, + private Scope, public SingleParameterDistributionBase { const std::vector elements; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index 81831d1f5a5..4f76fc0dd4c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -34,7 +34,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ struct UniformDistribution : public ComplexType, - protected Scope, + private Scope, public SingleParameterDistributionBase { const Range range; From e01a52828ee5a187f7e81a4f0960a384a26509e8 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 11 Apr 2023 13:33:55 +0900 Subject: [PATCH 057/120] fix(openscenario_preprocessor): fix probability_distribution_set.cpp --- .../src/syntax/probability_distribution_set.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp index a4f9d888214..93cc9fc2b44 100644 --- a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp @@ -39,7 +39,7 @@ ProbabilityDistributionSet::ProbabilityDistributionSet( std::vector ProbabilityDistributionSet::derive() { size_t index = distribute(random_engine); - return std::vector({elements.at(index)}); + return std::vector({make(elements.at(index).value)}); } } // namespace syntax } // namespace openscenario_interpreter From e6092b5af414e3467428f1ea1841bfbcb2020572 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 11 Apr 2023 15:49:01 +0900 Subject: [PATCH 058/120] feat(openscenario_interpreter): add getNumberOfDeriveScenarios() to distribution classes } --- .../parameter_distribution.hpp | 16 ++++++++++++++++ .../syntax/deterministic.hpp | 2 ++ ...eterministic_multi_parameter_distribution.hpp | 2 ++ ...terministic_single_parameter_distribution.hpp | 2 ++ .../syntax/distribution_range.hpp | 2 ++ .../syntax/distribution_set.hpp | 2 ++ .../syntax/histogram.hpp | 1 + .../syntax/parameter_value_distribution.hpp | 2 ++ .../syntax/stochastic.hpp | 2 ++ .../syntax/value_set_distribution.hpp | 2 ++ .../src/syntax/deterministic.cpp | 12 ++++++++++++ ...eterministic_multi_parameter_distribution.cpp | 5 +++++ ...terministic_single_parameter_distribution.cpp | 7 +++++++ .../src/syntax/distribution_range.cpp | 4 ++++ .../src/syntax/distribution_set.cpp | 2 ++ .../src/syntax/histogram.cpp | 1 + .../src/syntax/parameter_value_distribution.cpp | 7 +++++++ .../src/syntax/value_set_distribution.cpp | 5 +++++ 18 files changed, 76 insertions(+) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp index 6159ffb3661..399f58382fa 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -17,6 +17,7 @@ #include #include +#include #include #include #include @@ -33,17 +34,32 @@ using SingleUnnamedParameterDistribution = std::vector; struct SingleParameterDistributionBase { virtual auto derive() -> SingleUnnamedParameterDistribution = 0; + + virtual auto getNumberOfDeriveScenarios() const -> size_t + { + throw Error("getNumberOfDeriveScenarios() is not implemented"); + } }; struct MultiParameterDistributionBase { virtual auto derive() -> ParameterDistribution = 0; + + virtual auto getNumberOfDeriveScenarios() const -> size_t + { + throw Error("getNumberOfDeriveScenarios() is not implemented"); + } }; // container types of distribution data generator struct ParameterDistributionContainer { virtual auto derive() -> ParameterDistribution = 0; + + virtual auto getNumberOfDeriveScenarios() const -> size_t + { + throw Error("getNumberOfDeriveScenarios() is not implemented"); + } }; auto mergeParameterDistribution( diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp index ead4f0e68ce..f657d80e864 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp @@ -40,6 +40,8 @@ struct Deterministic : public ParameterDistributionContainer explicit Deterministic(const pugi::xml_node &, Scope & scope); auto derive() -> ParameterDistribution override; + + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp index 0cb03b365fd..1bffcfe6d1f 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp @@ -38,6 +38,8 @@ struct DeterministicMultiParameterDistribution : public DeterministicMultiParame explicit DeterministicMultiParameterDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> ParameterDistribution override; + + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index 3ac7b9c9515..0aea98c2fea 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -42,6 +42,8 @@ struct DeterministicSingleParameterDistribution explicit DeterministicSingleParameterDistribution(const pugi::xml_node &, Scope &); auto derive() -> ParameterDistribution override; + + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index d8ae87e1a20..ff188385f9d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -43,6 +43,8 @@ struct DistributionRange : private Scope, public ComplexType, public SingleParam explicit DistributionRange(const pugi::xml_node &, Scope &); auto derive() -> SingleUnnamedParameterDistribution override; + + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index 15c4a150b07..85fbcf56c93 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -39,6 +39,8 @@ struct DistributionSet : private Scope, public ComplexType, public SingleParamet explicit DistributionSet(const pugi::xml_node &, Scope & scope); auto derive() -> SingleUnnamedParameterDistribution override; + + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index b1f8bb50b9c..ab8c67b17de 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -59,6 +59,7 @@ struct Histogram : public ComplexType, protected Scope, public SingleParameterDi std::piecewise_constant_distribution distribute; explicit Histogram(const pugi::xml_node &, Scope & scope); + auto derive() -> std::vector override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp index 8197cf17d2a..de6e38eba18 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp @@ -40,6 +40,8 @@ struct ParameterValueDistribution : public DistributionDefinition, explicit ParameterValueDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> ParameterDistribution override; + + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp index 57c611541ae..d5a01d1b3e5 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp @@ -58,6 +58,8 @@ struct Stochastic : public ComplexType, public ParameterDistributionContainer } return distribution; } + + auto getNumberOfDeriveScenarios() const -> size_t override { return number_of_test_runs; } }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp index 15f0e7dd388..1dd69bf7dbd 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp @@ -39,6 +39,8 @@ struct ValueSetDistribution : public Scope, public MultiParameterDistributionBas explicit ValueSetDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> ParameterDistribution override; + + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp index 987b3483a83..96ecee10ad8 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp @@ -36,5 +36,17 @@ ParameterDistribution Deterministic::derive() } return distribution; } + +auto Deterministic::getNumberOfDeriveScenarios() const -> size_t +{ + return std::accumulate( + deterministic_parameter_distributions.begin(), deterministic_parameter_distributions.end(), 1, + [](size_t pre_result, auto distribution) { + return pre_result * + apply( + [](auto & distribution) { return distribution.getNumberOfDeriveScenarios(); }, + distribution); + }); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp index ff268236376..9361768c116 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp @@ -29,5 +29,10 @@ ParameterDistribution DeterministicMultiParameterDistribution::derive() { return DeterministicMultiParameterDistributionType::derive(); } + +auto DeterministicMultiParameterDistribution::getNumberOfDeriveScenarios() const -> size_t +{ + return DeterministicMultiParameterDistributionType::getNumberOfDeriveScenarios(); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp index 0e8f8b8423f..977a72e39ae 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp @@ -40,5 +40,12 @@ ParameterDistribution DeterministicSingleParameterDistribution::derive() }, *this); } + +auto DeterministicSingleParameterDistribution::getNumberOfDeriveScenarios() const -> size_t +{ + return apply( + [](auto & unnamed_distribution) { return unnamed_distribution.getNumberOfDeriveScenarios(); }, + (DeterministicSingleParameterDistributionType &)*this); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp index fbe0f16212b..6f60fc1c451 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp @@ -35,6 +35,10 @@ auto DistributionRange::derive() -> SingleUnnamedParameterDistribution } return unnamed_distribution; } +auto DistributionRange::getNumberOfDeriveScenarios() const -> size_t +{ + return int((range.upper_limit - range.lower_limit) / step_width) + 1; +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp index 7a023200e43..a0e00e96a7f 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp @@ -32,5 +32,7 @@ auto DistributionSet::derive() -> SingleUnnamedParameterDistribution } return distribution; } + +auto DistributionSet::getNumberOfDeriveScenarios() const -> size_t { return std::size(elements); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp index 9325d2073a7..cb3de535521 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp @@ -32,5 +32,6 @@ std::vector Histogram::derive() { return std::vector({make(distribute(random_engine))}); } + } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp index e4130e75d3c..63d2bc30740 100644 --- a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp @@ -30,5 +30,12 @@ ParameterDistribution ParameterValueDistribution::derive() return apply( [](auto & distribution) { return distribution.derive(); }, *this); } + +auto ParameterValueDistribution::getNumberOfDeriveScenarios() const -> size_t +{ + return apply( + [](auto & distribution) { return distribution.getNumberOfDeriveScenarios(); }, + (DistributionDefinition &)*this); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp index eafe1a64f2c..cf760b4af4e 100644 --- a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp @@ -34,5 +34,10 @@ auto ValueSetDistribution::derive() -> ParameterDistribution } return parameters; } + +auto ValueSetDistribution::getNumberOfDeriveScenarios() const -> size_t +{ + return std::size(parameter_value_sets); +} } // namespace syntax } // namespace openscenario_interpreter From c104f06fa39be3bb73d4531d0e0c225eed673f13 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 12 Apr 2023 11:32:20 +0900 Subject: [PATCH 059/120] feat(openscenario_interpreter): add derive() for single derivation of deterministic distribution classes } --- .../openscenario_interpreter/syntax/deterministic.hpp | 9 +++++++++ .../deterministic_multi_parameter_distribution.hpp | 4 ++++ .../deterministic_single_parameter_distribution.hpp | 10 ++++++++++ .../syntax/distribution_range.hpp | 5 +++++ .../syntax/distribution_set.hpp | 4 ++++ .../syntax/value_set_distribution.hpp | 4 ++++ 6 files changed, 36 insertions(+) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp index f657d80e864..32019b9e04a 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp @@ -41,6 +41,15 @@ struct Deterministic : public ParameterDistributionContainer auto derive() -> ParameterDistribution override; + auto derive(size_t index, size_t total_size) -> ParameterList + { + auto child = std::next(deterministic_parameter_distributions.begin(), std::floor(index / total_size)); + return apply([&](auto & child_distribution) { + return child_distribution.derive( + index % total_size, total_size / deterministic_parameter_distributions.size()); + }, (DeterministicParameterDistribution &)child); + } + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp index 1bffcfe6d1f..ea34b609744 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp @@ -39,6 +39,10 @@ struct DeterministicMultiParameterDistribution : public DeterministicMultiParame auto derive() -> ParameterDistribution override; + auto derive(size_t index, size_t total_size) -> ParameterList { + return DeterministicMultiParameterDistributionType::derive(index, total_size); + } + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index 0aea98c2fea..3b7bdc6a052 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -43,6 +43,16 @@ struct DeterministicSingleParameterDistribution auto derive() -> ParameterDistribution override; + auto derive(size_t index, size_t total_size) -> ParameterList + { + return { + {parameter_name, apply( + [index, total_size](auto && single_parameter_distribution) { + return single_parameter_distribution.derive(index, total_size); + }, + (DeterministicSingleParameterDistributionType &)*this)}}; + } + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index ff188385f9d..77b6d650c61 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -44,6 +44,11 @@ struct DistributionRange : private Scope, public ComplexType, public SingleParam auto derive() -> SingleUnnamedParameterDistribution override; + auto derive(size_t index, size_t total_size) -> Object + { + return make(range.lower_limit + step_width * index); + } + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index 85fbcf56c93..de3b951b05c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -40,6 +40,10 @@ struct DistributionSet : private Scope, public ComplexType, public SingleParamet auto derive() -> SingleUnnamedParameterDistribution override; + auto derive(size_t index, size_t total_size) -> Object { + return make(std::next(elements.begin(), index)->value); + } + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp index 1dd69bf7dbd..182c813b35c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp @@ -40,6 +40,10 @@ struct ValueSetDistribution : public Scope, public MultiParameterDistributionBas auto derive() -> ParameterDistribution override; + auto derive(size_t index, size_t total_size) -> ParameterList { + return *std::next(parameter_value_sets.begin(), index)->evaluate(); + } + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax From 491304eb91ff52008c9bda038f56151554fc877b Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 12 Apr 2023 11:32:47 +0900 Subject: [PATCH 060/120] chore: apply linter --- .../syntax/deterministic.hpp | 13 ++++++++----- .../deterministic_multi_parameter_distribution.hpp | 3 ++- .../syntax/distribution_set.hpp | 3 ++- .../syntax/value_set_distribution.hpp | 3 ++- 4 files changed, 14 insertions(+), 8 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp index 32019b9e04a..ed83548ff8c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp @@ -43,11 +43,14 @@ struct Deterministic : public ParameterDistributionContainer auto derive(size_t index, size_t total_size) -> ParameterList { - auto child = std::next(deterministic_parameter_distributions.begin(), std::floor(index / total_size)); - return apply([&](auto & child_distribution) { - return child_distribution.derive( - index % total_size, total_size / deterministic_parameter_distributions.size()); - }, (DeterministicParameterDistribution &)child); + auto child = + std::next(deterministic_parameter_distributions.begin(), std::floor(index / total_size)); + return apply( + [&](auto & child_distribution) { + return child_distribution.derive( + index % total_size, total_size / deterministic_parameter_distributions.size()); + }, + (DeterministicParameterDistribution &)child); } auto getNumberOfDeriveScenarios() const -> size_t override; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp index ea34b609744..ab67f523776 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp @@ -39,7 +39,8 @@ struct DeterministicMultiParameterDistribution : public DeterministicMultiParame auto derive() -> ParameterDistribution override; - auto derive(size_t index, size_t total_size) -> ParameterList { + auto derive(size_t index, size_t total_size) -> ParameterList + { return DeterministicMultiParameterDistributionType::derive(index, total_size); } diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index de3b951b05c..a40261807a0 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -40,7 +40,8 @@ struct DistributionSet : private Scope, public ComplexType, public SingleParamet auto derive() -> SingleUnnamedParameterDistribution override; - auto derive(size_t index, size_t total_size) -> Object { + auto derive(size_t index, size_t total_size) -> Object + { return make(std::next(elements.begin(), index)->value); } diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp index 182c813b35c..b88fe42f0df 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp @@ -40,7 +40,8 @@ struct ValueSetDistribution : public Scope, public MultiParameterDistributionBas auto derive() -> ParameterDistribution override; - auto derive(size_t index, size_t total_size) -> ParameterList { + auto derive(size_t index, size_t total_size) -> ParameterList + { return *std::next(parameter_value_sets.begin(), index)->evaluate(); } From 808748d10d9a058abbf3d6166fb610898ebd66fd Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 12 Apr 2023 16:44:18 +0900 Subject: [PATCH 061/120] chore(openscenario_preprocessor): fix build error --- .../src/openscenario_preprocessor.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp index 76391ad5322..0f6345fa2ab 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp @@ -45,7 +45,8 @@ void Preprocessor::preprocessScenario(ScenarioSet & scenario) .select_node(pugi::xpath_query{"/OpenSCENARIO/ParameterDeclarations"}) .node(); - for (const auto & [name, parameter] : *parameter_list.value()) { + // embedding parameter values + for (const auto & [name, value] : *parameter_list.value()) { if (auto parameter_node = parameter_declarations.find_child_by_attribute("name", name.c_str()); parameter_node) { From 31e2199e5c38dbc5767a61e40f348e5bf39d0068 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 14 Apr 2023 19:58:26 +0900 Subject: [PATCH 062/120] feat(openscenario_interpreter): implement derive() for parallel derivation --- .../parameter_distribution.hpp | 27 +++++++------- .../syntax/deterministic.hpp | 13 ++----- ...rministic_multi_parameter_distribution.hpp | 6 ++-- ...ministic_single_parameter_distribution.hpp | 11 ++---- .../syntax/distribution_range.hpp | 6 ++-- .../syntax/distribution_set.hpp | 6 ++-- .../syntax/histogram.hpp | 3 ++ .../syntax/normal_distribution.hpp | 3 ++ .../syntax/parameter_value_distribution.hpp | 3 ++ .../syntax/poisson_distribution.hpp | 3 ++ .../syntax/probability_distribution_set.hpp | 3 ++ .../syntax/stochastic.hpp | 17 ++++----- .../syntax/stochastic_distribution.hpp | 3 ++ .../syntax/uniform_distribution.hpp | 3 ++ .../syntax/value_set_distribution.hpp | 6 ++-- .../src/syntax/deterministic.cpp | 14 ++++++++ ...rministic_multi_parameter_distribution.cpp | 7 ++++ ...ministic_single_parameter_distribution.cpp | 14 ++++++++ .../src/syntax/distribution_range.cpp | 6 ++++ .../src/syntax/distribution_set.cpp | 6 ++++ .../src/syntax/histogram.cpp | 5 +++ .../src/syntax/normal_distribution.cpp | 6 ++++ .../syntax/parameter_value_distribution.cpp | 10 ++++++ .../src/syntax/poisson_distribution.cpp | 6 ++++ .../syntax/probability_distribution_set.cpp | 7 ++++ .../src/syntax/stochastic.cpp | 36 +++++++++++++++++-- .../src/syntax/stochastic_distribution.cpp | 14 ++++++++ .../src/syntax/uniform_distribution.cpp | 6 ++++ .../src/syntax/value_set_distribution.cpp | 6 ++++ 29 files changed, 191 insertions(+), 65 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp index 399f58382fa..9bb05450f2d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -30,10 +30,11 @@ using ParameterListSharedPtr = std::shared_ptr; using ParameterDistribution = std::vector; using SingleUnnamedParameterDistribution = std::vector; -// generator types distribution -struct SingleParameterDistributionBase +struct ParallelDerivableParameterDistributionBase { - virtual auto derive() -> SingleUnnamedParameterDistribution = 0; + virtual auto derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList = 0; virtual auto getNumberOfDeriveScenarios() const -> size_t { @@ -41,25 +42,21 @@ struct SingleParameterDistributionBase } }; -struct MultiParameterDistributionBase +// generator types distribution +struct SingleParameterDistributionBase : public ParallelDerivableParameterDistributionBase { - virtual auto derive() -> ParameterDistribution = 0; + virtual auto derive() -> SingleUnnamedParameterDistribution = 0; +}; - virtual auto getNumberOfDeriveScenarios() const -> size_t - { - throw Error("getNumberOfDeriveScenarios() is not implemented"); - } +struct MultiParameterDistributionBase : public ParallelDerivableParameterDistributionBase +{ + virtual auto derive() -> ParameterDistribution = 0; }; // container types of distribution data generator -struct ParameterDistributionContainer +struct ParameterDistributionContainer : public ParallelDerivableParameterDistributionBase { virtual auto derive() -> ParameterDistribution = 0; - - virtual auto getNumberOfDeriveScenarios() const -> size_t - { - throw Error("getNumberOfDeriveScenarios() is not implemented"); - } }; auto mergeParameterDistribution( diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp index ed83548ff8c..0cf8840f686 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp @@ -41,17 +41,8 @@ struct Deterministic : public ParameterDistributionContainer auto derive() -> ParameterDistribution override; - auto derive(size_t index, size_t total_size) -> ParameterList - { - auto child = - std::next(deterministic_parameter_distributions.begin(), std::floor(index / total_size)); - return apply( - [&](auto & child_distribution) { - return child_distribution.derive( - index % total_size, total_size / deterministic_parameter_distributions.size()); - }, - (DeterministicParameterDistribution &)child); - } + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; auto getNumberOfDeriveScenarios() const -> size_t override; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp index ab67f523776..f46d5a38309 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp @@ -39,10 +39,8 @@ struct DeterministicMultiParameterDistribution : public DeterministicMultiParame auto derive() -> ParameterDistribution override; - auto derive(size_t index, size_t total_size) -> ParameterList - { - return DeterministicMultiParameterDistributionType::derive(index, total_size); - } + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; auto getNumberOfDeriveScenarios() const -> size_t override; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index 3b7bdc6a052..d7588b0b02f 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -43,15 +43,8 @@ struct DeterministicSingleParameterDistribution auto derive() -> ParameterDistribution override; - auto derive(size_t index, size_t total_size) -> ParameterList - { - return { - {parameter_name, apply( - [index, total_size](auto && single_parameter_distribution) { - return single_parameter_distribution.derive(index, total_size); - }, - (DeterministicSingleParameterDistributionType &)*this)}}; - } + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; auto getNumberOfDeriveScenarios() const -> size_t override; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index 77b6d650c61..8815e1c2673 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -44,10 +44,8 @@ struct DistributionRange : private Scope, public ComplexType, public SingleParam auto derive() -> SingleUnnamedParameterDistribution override; - auto derive(size_t index, size_t total_size) -> Object - { - return make(range.lower_limit + step_width * index); - } + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; auto getNumberOfDeriveScenarios() const -> size_t override; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index a40261807a0..b8beed33477 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -40,10 +40,8 @@ struct DistributionSet : private Scope, public ComplexType, public SingleParamet auto derive() -> SingleUnnamedParameterDistribution override; - auto derive(size_t index, size_t total_size) -> Object - { - return make(std::next(elements.begin(), index)->value); - } + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; auto getNumberOfDeriveScenarios() const -> size_t override; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index ab8c67b17de..a55cd40eee4 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -61,6 +61,9 @@ struct Histogram : public ComplexType, protected Scope, public SingleParameterDi explicit Histogram(const pugi::xml_node &, Scope & scope); auto derive() -> std::vector override; + + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp index aacf1078447..73ea9b19f68 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp @@ -53,6 +53,9 @@ struct NormalDistribution : public ComplexType, explicit NormalDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> std::vector override; + + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp index de6e38eba18..a1e32684229 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp @@ -41,6 +41,9 @@ struct ParameterValueDistribution : public DistributionDefinition, auto derive() -> ParameterDistribution override; + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; + auto getNumberOfDeriveScenarios() const -> size_t override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index 9cfbf59db3d..bd1463fa672 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -48,6 +48,9 @@ struct PoissonDistribution : public ComplexType, explicit PoissonDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> std::vector override; + + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index 09481874137..a1eab5da13c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -58,6 +58,9 @@ struct ProbabilityDistributionSet : public ComplexType, explicit ProbabilityDistributionSet(const pugi::xml_node &, Scope & scope); auto derive() -> std::vector override; + + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp index d5a01d1b3e5..cca4dbb0ea7 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp @@ -39,25 +39,20 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ -struct Stochastic : public ComplexType, public ParameterDistributionContainer +struct Stochastic : public ComplexType, public ParameterDistributionContainer, private Scope { const UnsignedInt number_of_test_runs; const Double random_seed; - StochasticDistribution stochastic_distribution; + std::list stochastic_distributions; explicit Stochastic(const pugi::xml_node &, Scope & scope); - auto derive() -> ParameterDistribution override - { - ParameterDistribution distribution; - for (size_t i = 0; i < number_of_test_runs; i++) { - auto derived = stochastic_distribution.derive(); - distribution.insert(distribution.end(), derived.begin(), derived.end()); - } - return distribution; - } + auto derive() -> ParameterDistribution override; + + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; auto getNumberOfDeriveScenarios() const -> size_t override { return number_of_test_runs; } }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp index fbded25eec6..b59bb89cfa3 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp @@ -42,6 +42,9 @@ struct StochasticDistribution : public StochasticDistributionType, explicit StochasticDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> ParameterDistribution override; + + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index 4f76fc0dd4c..cfc7da5770a 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -44,6 +44,9 @@ struct UniformDistribution : public ComplexType, explicit UniformDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> std::vector override; + + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp index b88fe42f0df..617074bb4b5 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp @@ -40,10 +40,8 @@ struct ValueSetDistribution : public Scope, public MultiParameterDistributionBas auto derive() -> ParameterDistribution override; - auto derive(size_t index, size_t total_size) -> ParameterList - { - return *std::next(parameter_value_sets.begin(), index)->evaluate(); - } + auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + -> ParameterList override; auto getNumberOfDeriveScenarios() const -> size_t override; }; diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp index 96ecee10ad8..48f960a577f 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp @@ -48,5 +48,19 @@ auto Deterministic::getNumberOfDeriveScenarios() const -> size_t distribution); }); } + +auto Deterministic::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList +{ + auto child = + std::next(deterministic_parameter_distributions.begin(), std::floor(local_index / local_size)); + return apply( + [&](auto & child_distribution) { + return child_distribution.derive( + local_index % local_size, local_size / deterministic_parameter_distributions.size(), + global_index, global_size); + }, + (DeterministicParameterDistribution &)*child); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp index 9361768c116..130a7f18356 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp @@ -34,5 +34,12 @@ auto DeterministicMultiParameterDistribution::getNumberOfDeriveScenarios() const { return DeterministicMultiParameterDistributionType::getNumberOfDeriveScenarios(); } + +auto DeterministicMultiParameterDistribution::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList +{ + return DeterministicMultiParameterDistributionType::derive( + local_index, local_size, global_index, global_size); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp index 977a72e39ae..fb64e06b07c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp @@ -47,5 +47,19 @@ auto DeterministicSingleParameterDistribution::getNumberOfDeriveScenarios() cons [](auto & unnamed_distribution) { return unnamed_distribution.getNumberOfDeriveScenarios(); }, (DeterministicSingleParameterDistributionType &)*this); } + +auto DeterministicSingleParameterDistribution::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList +{ + return { + {parameter_name, apply( + [&](auto && single_parameter_distribution) { + return single_parameter_distribution.derive( + local_index, local_size, global_index, global_size); + }, + (DeterministicSingleParameterDistributionType &)*this) + .begin() + ->second}}; +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp index 6f60fc1c451..79ecea407b9 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp @@ -40,5 +40,11 @@ auto DistributionRange::getNumberOfDeriveScenarios() const -> size_t return int((range.upper_limit - range.lower_limit) / step_width) + 1; } +auto DistributionRange::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList +{ + return ParameterList({{"", make(range.lower_limit + step_width * local_index)}}); +} + } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp index a0e00e96a7f..5b2c8e6290a 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp @@ -34,5 +34,11 @@ auto DistributionSet::derive() -> SingleUnnamedParameterDistribution } auto DistributionSet::getNumberOfDeriveScenarios() const -> size_t { return std::size(elements); } + +auto DistributionSet::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList +{ + return ParameterList({{"", make(std::next(elements.begin(), local_index)->value)}}); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp index cb3de535521..e8bd5e21edc 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp @@ -32,6 +32,11 @@ std::vector Histogram::derive() { return std::vector({make(distribute(random_engine))}); } +ParameterList Histogram::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) +{ + return ParameterList({{"", make(distribute(random_engine))}}); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp index 0fd89ba066c..4947a8703da 100644 --- a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp @@ -32,5 +32,11 @@ std::vector NormalDistribution::derive() { return std::vector({make(distribute(random_engine))}); } + +ParameterList NormalDistribution::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) +{ + return ParameterList({{"", make(distribute(random_engine))}}); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp index 63d2bc30740..c7b2f9fad33 100644 --- a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp @@ -37,5 +37,15 @@ auto ParameterValueDistribution::getNumberOfDeriveScenarios() const -> size_t [](auto & distribution) { return distribution.getNumberOfDeriveScenarios(); }, (DistributionDefinition &)*this); } + +ParameterList ParameterValueDistribution::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) +{ + return apply( + [&](auto & distribution) { + return distribution.derive(local_index, local_size, global_index, global_size); + }, + (DistributionDefinition &)*this); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp index 3597072385d..6b8027044bf 100644 --- a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp @@ -32,5 +32,11 @@ std::vector PoissonDistribution::derive() { return std::vector({make(range.evaluate(distribute(random_engine)))}); } + +ParameterList PoissonDistribution::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) +{ + return ParameterList({{"", make(range.evaluate(distribute(random_engine)))}}); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp index 93cc9fc2b44..2739cf8b2b6 100644 --- a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp @@ -41,5 +41,12 @@ std::vector ProbabilityDistributionSet::derive() size_t index = distribute(random_engine); return std::vector({make(elements.at(index).value)}); } + +ParameterList ProbabilityDistributionSet::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) +{ + size_t index = distribute(random_engine); + return ParameterList{{"", make(elements.at(index).value)}}; +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp index 15df998b6f0..501cdab2bcc 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp @@ -25,15 +25,45 @@ inline namespace syntax * so it may change in the future. */ Stochastic::Stochastic(const pugi::xml_node & node, Scope & scope) -: number_of_test_runs(readAttribute("numberOfTestRuns", node, scope)), +: Scope(scope), + number_of_test_runs(readAttribute("numberOfTestRuns", node, scope)), random_seed([&] { auto seed = static_cast(readAttribute("randomSeed", node, scope, 0)); scope.random_engine.seed(seed); return seed; }()), - stochastic_distribution( - readElement("StochasticDistribution", node, scope)) + stochastic_distributions( + readElements("StochasticDistribution", node, scope)) { } + +auto Stochastic::derive() -> ParameterDistribution +{ + ParameterDistribution distribution; + for (size_t i = 0; i < number_of_test_runs; i++) { + ParameterListSharedPtr parameter_list = std::make_shared(); + for (auto & stochastic_distribution : stochastic_distributions) { + auto derived = stochastic_distribution.derive(); + distribution.insert(distribution.end(), derived.begin(), derived.end()); + } + distribution.emplace_back(parameter_list); + } + return distribution; +} + +ParameterList Stochastic::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) +{ + // update random_engine + random_engine.seed(random_seed); + random_engine.discard(global_index); + + // N test_runs : i (0 <= i < N) + // M distributions : j (0 <= j < M) + // index : i * M + j + return std::next(stochastic_distributions.begin(), local_index % stochastic_distributions.size()) + ->derive(local_index, local_size, global_index, global_size); +} + } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp index c83555ec530..3a4704c5117 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp @@ -38,5 +38,19 @@ auto StochasticDistribution::derive() -> ParameterDistribution }, *this); } + +ParameterList StochasticDistribution::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) +{ + return { + {parameter_name, make(apply( + [&](auto & unnamed_distribution) { + return unnamed_distribution.derive( + local_index, local_size, global_index, global_size); + }, + (StochasticDistributionType &)*this) + .begin() + ->second)}}; +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index 28ac8ba44c4..58f3e8cdb82 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -31,5 +31,11 @@ std::vector UniformDistribution::derive() { return std::vector({make(distribute(random_engine))}); } + +ParameterList UniformDistribution::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) +{ + return ParameterList({{"", make(distribute(random_engine))}}); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp index cf760b4af4e..4d4518fce36 100644 --- a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp @@ -39,5 +39,11 @@ auto ValueSetDistribution::getNumberOfDeriveScenarios() const -> size_t { return std::size(parameter_value_sets); } + +auto ValueSetDistribution::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList +{ + return *(std::next(parameter_value_sets.begin(), local_index)->evaluate()); +} } // namespace syntax } // namespace openscenario_interpreter From c2fa772be638c3a6dd012f461278d31df25cc3fb Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 14 Apr 2023 20:46:59 +0900 Subject: [PATCH 063/120] chore(openscenario_interpreter): fix unnecessary inherit access --- .../include/openscenario_interpreter/syntax/histogram.hpp | 2 +- .../syntax/user_defined_distribution.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index a55cd40eee4..b023ba21f62 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -34,7 +34,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ -struct Histogram : public ComplexType, protected Scope, public SingleParameterDistributionBase +struct Histogram : public ComplexType, private Scope, public SingleParameterDistributionBase { /** * Note: HistogramBin must be stored in continuous range and ascending order to `bins` diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp index fe6ede458ea..6f8d552cfbd 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp @@ -33,7 +33,7 @@ inline namespace syntax * * * -------------------------------------------------------------------------- */ -struct UserDefinedDistribution : protected Scope, public ComplexType +struct UserDefinedDistribution : private Scope, public ComplexType { const String type; From 9e7793165ee11970621496ce28b982a0f01b5ca3 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 14 Apr 2023 21:12:35 +0900 Subject: [PATCH 064/120] chore(openscenario_preprocessor): fix indent of package.xml --- openscenario/openscenario_preprocessor/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 1a1ec2ed6d9..dd7c018ec7d 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -10,7 +10,6 @@ ament_cmake_auto - libgoogle-glog-dev openscenario_interpreter openscenario_preprocessor_msgs rclcpp From 688e180065421108e16d9197f7547057ab06f1fe Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 14 Apr 2023 21:13:04 +0900 Subject: [PATCH 065/120] chore(openscenario_preprocessor): delete unused code --- .../src/openscenario_preprocessor.cpp | 2 ++ .../src/openscenario_preprocessor_node.cpp | 5 ----- 2 files changed, 2 insertions(+), 5 deletions(-) diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp index 0f6345fa2ab..09e1097ae54 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp @@ -35,8 +35,10 @@ void Preprocessor::preprocessScenario(ScenarioSet & scenario) if (xml_validator.validate(base_scenario_path)) { auto base_scenario = std::make_shared(base_scenario_path); auto p = parameter_value_distribution.derive(); + std::cout << "Number of derived scenarios: " << p.size() << std::endl; for (const auto & parameter_list : p | boost::adaptors::indexed()) { + std::cout << "scenario number : " << parameter_list.index() << std::endl; pugi::xml_document derived_script; derived_script.reset(base_scenario->script); // deep copy diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp index 66e05b54cfb..83536431d7b 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp @@ -12,8 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. -//#include - #include #include #include @@ -90,9 +88,6 @@ class PreprocessorNode : public rclcpp::Node, public openscenario_preprocessor:: int main(const int argc, char const * const * const argv) { - // google::InitGoogleLogging(argv[0]); - // google::InstallFailureSignalHandler(); - rclcpp::init(argc, argv); rclcpp::executors::SingleThreadedExecutor executor{}; From 8b35b94d722bedeb5b09eadaf2d4736f1173ff5f Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 14 Apr 2023 21:19:42 +0900 Subject: [PATCH 066/120] refactor(openscenario_interpreter) --- .../syntax/probability_distribution_set.hpp | 2 +- .../syntax/uniform_distribution.hpp | 2 +- .../src/syntax/deterministic.cpp | 26 +++++++++---------- ...rministic_multi_parameter_distribution.cpp | 12 ++++----- ...ministic_single_parameter_distribution.cpp | 16 ++++++------ .../src/syntax/distribution_range.cpp | 8 +++--- .../src/syntax/distribution_set.cpp | 4 +-- .../src/syntax/histogram.cpp | 8 +++--- .../src/syntax/normal_distribution.cpp | 7 ++--- .../syntax/parameter_value_distribution.cpp | 6 ++--- .../src/syntax/poisson_distribution.cpp | 2 +- .../syntax/probability_distribution_set.cpp | 6 ++--- .../src/syntax/stochastic.cpp | 4 +-- .../src/syntax/stochastic_distribution.cpp | 4 +-- .../src/syntax/uniform_distribution.cpp | 6 ++--- .../src/syntax/value_set_distribution.cpp | 10 +++---- 16 files changed, 62 insertions(+), 61 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index a1eab5da13c..70938efbaa6 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -57,7 +57,7 @@ struct ProbabilityDistributionSet : public ComplexType, explicit ProbabilityDistributionSet(const pugi::xml_node &, Scope & scope); - auto derive() -> std::vector override; + auto derive() -> SingleUnnamedParameterDistribution override; auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList override; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index cfc7da5770a..227d33e1a7a 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -43,7 +43,7 @@ struct UniformDistribution : public ComplexType, explicit UniformDistribution(const pugi::xml_node &, Scope & scope); - auto derive() -> std::vector override; + auto derive() -> SingleUnnamedParameterDistribution override; auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList override; diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp index 48f960a577f..82b7ddf4f1f 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp @@ -25,7 +25,7 @@ Deterministic::Deterministic(const pugi::xml_node & node, Scope & scope) { } -ParameterDistribution Deterministic::derive() +auto Deterministic::derive() -> ParameterDistribution { ParameterDistribution distribution; for (auto additional_distribution : deterministic_parameter_distributions) { @@ -37,18 +37,6 @@ ParameterDistribution Deterministic::derive() return distribution; } -auto Deterministic::getNumberOfDeriveScenarios() const -> size_t -{ - return std::accumulate( - deterministic_parameter_distributions.begin(), deterministic_parameter_distributions.end(), 1, - [](size_t pre_result, auto distribution) { - return pre_result * - apply( - [](auto & distribution) { return distribution.getNumberOfDeriveScenarios(); }, - distribution); - }); -} - auto Deterministic::derive( size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList { @@ -62,5 +50,17 @@ auto Deterministic::derive( }, (DeterministicParameterDistribution &)*child); } + +auto Deterministic::getNumberOfDeriveScenarios() const -> size_t +{ + return std::accumulate( + deterministic_parameter_distributions.begin(), deterministic_parameter_distributions.end(), 1, + [](size_t pre_result, auto distribution) { + return pre_result * + apply( + [](auto & distribution) { return distribution.getNumberOfDeriveScenarios(); }, + distribution); + }); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp index 130a7f18356..e68c2bcfc11 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp @@ -25,21 +25,21 @@ DeterministicMultiParameterDistribution::DeterministicMultiParameterDistribution { } -ParameterDistribution DeterministicMultiParameterDistribution::derive() +auto DeterministicMultiParameterDistribution::derive() -> ParameterDistribution { return DeterministicMultiParameterDistributionType::derive(); } -auto DeterministicMultiParameterDistribution::getNumberOfDeriveScenarios() const -> size_t -{ - return DeterministicMultiParameterDistributionType::getNumberOfDeriveScenarios(); -} - auto DeterministicMultiParameterDistribution::derive( size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList { return DeterministicMultiParameterDistributionType::derive( local_index, local_size, global_index, global_size); } + +auto DeterministicMultiParameterDistribution::getNumberOfDeriveScenarios() const -> size_t +{ + return DeterministicMultiParameterDistributionType::getNumberOfDeriveScenarios(); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp index fb64e06b07c..06ac15a5243 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp @@ -26,7 +26,7 @@ DeterministicSingleParameterDistribution::DeterministicSingleParameterDistributi { } -ParameterDistribution DeterministicSingleParameterDistribution::derive() +auto DeterministicSingleParameterDistribution::derive() -> ParameterDistribution { ParameterDistribution distribution; return apply( @@ -41,13 +41,6 @@ ParameterDistribution DeterministicSingleParameterDistribution::derive() *this); } -auto DeterministicSingleParameterDistribution::getNumberOfDeriveScenarios() const -> size_t -{ - return apply( - [](auto & unnamed_distribution) { return unnamed_distribution.getNumberOfDeriveScenarios(); }, - (DeterministicSingleParameterDistributionType &)*this); -} - auto DeterministicSingleParameterDistribution::derive( size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList { @@ -61,5 +54,12 @@ auto DeterministicSingleParameterDistribution::derive( .begin() ->second}}; } + +auto DeterministicSingleParameterDistribution::getNumberOfDeriveScenarios() const -> size_t +{ + return apply( + [](auto & unnamed_distribution) { return unnamed_distribution.getNumberOfDeriveScenarios(); }, + (DeterministicSingleParameterDistributionType &)*this); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp index 79ecea407b9..661747d9dd8 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp @@ -35,10 +35,6 @@ auto DistributionRange::derive() -> SingleUnnamedParameterDistribution } return unnamed_distribution; } -auto DistributionRange::getNumberOfDeriveScenarios() const -> size_t -{ - return int((range.upper_limit - range.lower_limit) / step_width) + 1; -} auto DistributionRange::derive( size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList @@ -46,5 +42,9 @@ auto DistributionRange::derive( return ParameterList({{"", make(range.lower_limit + step_width * local_index)}}); } +auto DistributionRange::getNumberOfDeriveScenarios() const -> size_t +{ + return int((range.upper_limit - range.lower_limit) / step_width) + 1; +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp index 5b2c8e6290a..c9abd43be6c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp @@ -33,12 +33,12 @@ auto DistributionSet::derive() -> SingleUnnamedParameterDistribution return distribution; } -auto DistributionSet::getNumberOfDeriveScenarios() const -> size_t { return std::size(elements); } - auto DistributionSet::derive( size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList { return ParameterList({{"", make(std::next(elements.begin(), local_index)->value)}}); } + +auto DistributionSet::getNumberOfDeriveScenarios() const -> size_t { return std::size(elements); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp index e8bd5e21edc..ab43c86836d 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp @@ -28,15 +28,15 @@ Histogram::Histogram(const pugi::xml_node & node, openscenario_interpreter::Scop { } -std::vector Histogram::derive() +auto Histogram::derive() -> SingleUnnamedParameterDistribution { return std::vector({make(distribute(random_engine))}); } -ParameterList Histogram::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) + +auto Histogram::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList { return ParameterList({{"", make(distribute(random_engine))}}); } - } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp index 4947a8703da..bcf7711890f 100644 --- a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp @@ -28,13 +28,14 @@ NormalDistribution::NormalDistribution( distribute(static_cast(expected_value.data), static_cast(variance.data)) { } -std::vector NormalDistribution::derive() + +auto NormalDistribution::derive() -> SingleUnnamedParameterDistribution { return std::vector({make(distribute(random_engine))}); } -ParameterList NormalDistribution::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) +auto NormalDistribution::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList { return ParameterList({{"", make(distribute(random_engine))}}); } diff --git a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp index c7b2f9fad33..ff21c96e2d4 100644 --- a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp @@ -25,7 +25,7 @@ ParameterValueDistribution::ParameterValueDistribution( { } -ParameterDistribution ParameterValueDistribution::derive() +auto ParameterValueDistribution::derive() -> ParameterDistribution { return apply( [](auto & distribution) { return distribution.derive(); }, *this); @@ -38,8 +38,8 @@ auto ParameterValueDistribution::getNumberOfDeriveScenarios() const -> size_t (DistributionDefinition &)*this); } -ParameterList ParameterValueDistribution::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) +auto ParameterValueDistribution::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList { return apply( [&](auto & distribution) { diff --git a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp index 6b8027044bf..0f6bfac0c1c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp @@ -28,7 +28,7 @@ PoissonDistribution::PoissonDistribution( { } -std::vector PoissonDistribution::derive() +auto PoissonDistribution::derive() -> SingleUnnamedParameterDistribution { return std::vector({make(range.evaluate(distribute(random_engine)))}); } diff --git a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp index 2739cf8b2b6..ab8d23b2623 100644 --- a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp @@ -36,14 +36,14 @@ ProbabilityDistributionSet::ProbabilityDistributionSet( { } -std::vector ProbabilityDistributionSet::derive() +auto ProbabilityDistributionSet::derive() -> SingleUnnamedParameterDistribution { size_t index = distribute(random_engine); return std::vector({make(elements.at(index).value)}); } -ParameterList ProbabilityDistributionSet::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) +auto ProbabilityDistributionSet::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList { size_t index = distribute(random_engine); return ParameterList{{"", make(elements.at(index).value)}}; diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp index 501cdab2bcc..edef2b52ca3 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp @@ -51,8 +51,8 @@ auto Stochastic::derive() -> ParameterDistribution return distribution; } -ParameterList Stochastic::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) +auto Stochastic::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList { // update random_engine random_engine.seed(random_seed); diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp index 3a4704c5117..2709d95aa1b 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp @@ -39,8 +39,8 @@ auto StochasticDistribution::derive() -> ParameterDistribution *this); } -ParameterList StochasticDistribution::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) +auto StochasticDistribution::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList { return { {parameter_name, make(apply( diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index 58f3e8cdb82..9529cef6e7c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -27,13 +27,13 @@ UniformDistribution::UniformDistribution( { } -std::vector UniformDistribution::derive() +auto UniformDistribution::derive() -> SingleUnnamedParameterDistribution { return std::vector({make(distribute(random_engine))}); } -ParameterList UniformDistribution::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) +auto UniformDistribution::derive( + size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList { return ParameterList({{"", make(distribute(random_engine))}}); } diff --git a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp index 4d4518fce36..1c05304bbfc 100644 --- a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp @@ -35,15 +35,15 @@ auto ValueSetDistribution::derive() -> ParameterDistribution return parameters; } -auto ValueSetDistribution::getNumberOfDeriveScenarios() const -> size_t -{ - return std::size(parameter_value_sets); -} - auto ValueSetDistribution::derive( size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList { return *(std::next(parameter_value_sets.begin(), local_index)->evaluate()); } + +auto ValueSetDistribution::getNumberOfDeriveScenarios() const -> size_t +{ + return std::size(parameter_value_sets); +} } // namespace syntax } // namespace openscenario_interpreter From b5c29bf3c7409bccb9f68b3d80a62484b82d765d Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 17 Apr 2023 10:47:29 +0900 Subject: [PATCH 067/120] apply linter --- .../include/openscenario_interpreter/reader/attribute.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/reader/attribute.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/reader/attribute.hpp index cba7466bdfb..06568802cbe 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/reader/attribute.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/reader/attribute.hpp @@ -81,7 +81,8 @@ auto substitute(std::string attribute, Scope & scope) // TODO {"find-exec", find_exec}, // TODO {"find-pkg-prefix", find_pkg_prefix}, {"find-pkg-share", find_pkg_share}, - {"ros2", ros2}, // NOTE: TIER IV extension (Not included in the ROS 2 Launch XML Substitution) + {"ros2", + ros2}, // NOTE: TIER IV extension (Not included in the ROS 2 Launch XML Substitution) {"var", var}, }; From 261cf776a6bdb930652646f865083fbc2c16d34a Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 17 Apr 2023 15:11:25 +0900 Subject: [PATCH 068/120] chore(openscenario_preprocessor): delete debug lines --- .../openscenario_preprocessor/src/openscenario_preprocessor.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp index 09e1097ae54..0f6345fa2ab 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp @@ -35,10 +35,8 @@ void Preprocessor::preprocessScenario(ScenarioSet & scenario) if (xml_validator.validate(base_scenario_path)) { auto base_scenario = std::make_shared(base_scenario_path); auto p = parameter_value_distribution.derive(); - std::cout << "Number of derived scenarios: " << p.size() << std::endl; for (const auto & parameter_list : p | boost::adaptors::indexed()) { - std::cout << "scenario number : " << parameter_list.index() << std::endl; pugi::xml_document derived_script; derived_script.reset(base_scenario->script); // deep copy From 8ba9d369793d39af7569e81515bbf06e37224099 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 17 Apr 2023 15:13:33 +0900 Subject: [PATCH 069/120] refactor(openscenario_interpreter): refactor base class --- .../parameter_distribution.hpp | 5 +++++ .../openscenario_interpreter/syntax/histogram.hpp | 4 ++-- .../syntax/normal_distribution.hpp | 4 ++-- .../syntax/poisson_distribution.hpp | 4 ++-- .../syntax/probability_distribution_set.hpp | 4 ++-- .../syntax/stochastic_distribution.hpp | 4 ++-- .../syntax/uniform_distribution.hpp | 4 ++-- .../src/syntax/histogram.cpp | 5 +---- .../src/syntax/normal_distribution.cpp | 5 +---- .../src/syntax/poisson_distribution.cpp | 4 ++-- .../src/syntax/probability_distribution_set.cpp | 4 ++-- .../src/syntax/stochastic.cpp | 2 +- .../src/syntax/stochastic_distribution.cpp | 14 +++----------- .../src/syntax/uniform_distribution.cpp | 5 +---- 14 files changed, 28 insertions(+), 40 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp index 9bb05450f2d..1045b1d511c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -53,6 +53,11 @@ struct MultiParameterDistributionBase : public ParallelDerivableParameterDistrib virtual auto derive() -> ParameterDistribution = 0; }; +struct StochasticParameterDistributionBase : public ParallelDerivableParameterDistributionBase +{ + virtual auto derive() -> Object = 0; +}; + // container types of distribution data generator struct ParameterDistributionContainer : public ParallelDerivableParameterDistributionBase { diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index b023ba21f62..e11e2db24ec 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -34,7 +34,7 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ -struct Histogram : public ComplexType, private Scope, public SingleParameterDistributionBase +struct Histogram : public ComplexType, private Scope, public StochasticParameterDistributionBase { /** * Note: HistogramBin must be stored in continuous range and ascending order to `bins` @@ -60,7 +60,7 @@ struct Histogram : public ComplexType, private Scope, public SingleParameterDist explicit Histogram(const pugi::xml_node &, Scope & scope); - auto derive() -> std::vector override; + auto derive() -> Object override; auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList override; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp index 73ea9b19f68..b62c705b1d4 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp @@ -40,7 +40,7 @@ inline namespace syntax struct NormalDistribution : public ComplexType, private Scope, - public SingleParameterDistributionBase + public StochasticParameterDistributionBase { const Range range; @@ -52,7 +52,7 @@ struct NormalDistribution : public ComplexType, explicit NormalDistribution(const pugi::xml_node &, Scope & scope); - auto derive() -> std::vector override; + auto derive() -> Object override; auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList override; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index bd1463fa672..5497ac73fdf 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -37,7 +37,7 @@ inline namespace syntax * -------------------------------------------------------------------------- */ struct PoissonDistribution : public ComplexType, private Scope, - public SingleParameterDistributionBase + public StochasticParameterDistributionBase { const Range range; @@ -47,7 +47,7 @@ struct PoissonDistribution : public ComplexType, explicit PoissonDistribution(const pugi::xml_node &, Scope & scope); - auto derive() -> std::vector override; + auto derive() -> Object override; auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList override; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index 70938efbaa6..86e74ea447b 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -35,7 +35,7 @@ inline namespace syntax struct ProbabilityDistributionSet : public ComplexType, private Scope, - public SingleParameterDistributionBase + public StochasticParameterDistributionBase { const std::vector elements; @@ -57,7 +57,7 @@ struct ProbabilityDistributionSet : public ComplexType, explicit ProbabilityDistributionSet(const pugi::xml_node &, Scope & scope); - auto derive() -> SingleUnnamedParameterDistribution override; + auto derive() -> Object override; auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList override; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp index b59bb89cfa3..7ab17f62762 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp @@ -35,13 +35,13 @@ inline namespace syntax * * -------------------------------------------------------------------------- */ struct StochasticDistribution : public StochasticDistributionType, - public ParameterDistributionContainer + public StochasticParameterDistributionBase { const String parameter_name; explicit StochasticDistribution(const pugi::xml_node &, Scope & scope); - auto derive() -> ParameterDistribution override; + auto derive() -> Object override; auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList override; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index 227d33e1a7a..663f4ce37aa 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -35,7 +35,7 @@ inline namespace syntax * -------------------------------------------------------------------------- */ struct UniformDistribution : public ComplexType, private Scope, - public SingleParameterDistributionBase + public StochasticParameterDistributionBase { const Range range; @@ -43,7 +43,7 @@ struct UniformDistribution : public ComplexType, explicit UniformDistribution(const pugi::xml_node &, Scope & scope); - auto derive() -> SingleUnnamedParameterDistribution override; + auto derive() -> Object override; auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList override; diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp index ab43c86836d..9b7d3ee589a 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp @@ -28,10 +28,7 @@ Histogram::Histogram(const pugi::xml_node & node, openscenario_interpreter::Scop { } -auto Histogram::derive() -> SingleUnnamedParameterDistribution -{ - return std::vector({make(distribute(random_engine))}); -} +auto Histogram::derive() -> Object { return make(distribute(random_engine)); } auto Histogram::derive( size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList diff --git a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp index bcf7711890f..4ea4362ae62 100644 --- a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp @@ -29,10 +29,7 @@ NormalDistribution::NormalDistribution( { } -auto NormalDistribution::derive() -> SingleUnnamedParameterDistribution -{ - return std::vector({make(distribute(random_engine))}); -} +auto NormalDistribution::derive() -> Object { return make(distribute(random_engine)); } auto NormalDistribution::derive( size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList diff --git a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp index 0f6bfac0c1c..22553b2fa85 100644 --- a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp @@ -28,9 +28,9 @@ PoissonDistribution::PoissonDistribution( { } -auto PoissonDistribution::derive() -> SingleUnnamedParameterDistribution +auto PoissonDistribution::derive() -> Object { - return std::vector({make(range.evaluate(distribute(random_engine)))}); + return make(range.evaluate(distribute(random_engine))); } ParameterList PoissonDistribution::derive( diff --git a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp index ab8d23b2623..389d94fd74b 100644 --- a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp @@ -36,10 +36,10 @@ ProbabilityDistributionSet::ProbabilityDistributionSet( { } -auto ProbabilityDistributionSet::derive() -> SingleUnnamedParameterDistribution +auto ProbabilityDistributionSet::derive() -> Object { size_t index = distribute(random_engine); - return std::vector({make(elements.at(index).value)}); + return make(elements.at(index).value); } auto ProbabilityDistributionSet::derive( diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp index edef2b52ca3..44c60b45c61 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp @@ -44,7 +44,7 @@ auto Stochastic::derive() -> ParameterDistribution ParameterListSharedPtr parameter_list = std::make_shared(); for (auto & stochastic_distribution : stochastic_distributions) { auto derived = stochastic_distribution.derive(); - distribution.insert(distribution.end(), derived.begin(), derived.end()); + parameter_list->emplace(stochastic_distribution.parameter_name, derived); } distribution.emplace_back(parameter_list); } diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp index 2709d95aa1b..b56ce3cd806 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp @@ -25,18 +25,10 @@ StochasticDistribution::StochasticDistribution(const pugi::xml_node & node, Scop { } -auto StochasticDistribution::derive() -> ParameterDistribution +auto StochasticDistribution::derive() -> Object { - return apply( - [this](auto & unnamed_distribution) { - ParameterDistribution distribution; - for (const auto & parameter : unnamed_distribution.derive()) { - distribution.emplace_back( - std::make_shared(ParameterList{{parameter_name, make(parameter)}})); - } - return distribution; - }, - *this); + return apply( + [](auto & unnamed_distribution) { return unnamed_distribution.derive(); }, *this); } auto StochasticDistribution::derive( diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index 9529cef6e7c..ebf5f9577c9 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -27,10 +27,7 @@ UniformDistribution::UniformDistribution( { } -auto UniformDistribution::derive() -> SingleUnnamedParameterDistribution -{ - return std::vector({make(distribute(random_engine))}); -} +auto UniformDistribution::derive() -> Object { return make(distribute(random_engine)); } auto UniformDistribution::derive( size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList From 2f9c1ffae71bccd5e4e98489265b675f83d4dcb4 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 17 Apr 2023 16:04:07 +0900 Subject: [PATCH 070/120] feat(openscenario_preprocessor): change derived scenario extension --- .../src/openscenario_preprocessor.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp index 0f6345fa2ab..48652e67128 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp @@ -64,8 +64,7 @@ void Preprocessor::preprocessScenario(ScenarioSet & scenario) boost::filesystem::path derived_scenario_path(derived_scenario.path); derived_scenario_path = output_directory / derived_scenario_path.filename(); derived_scenario_path.replace_extension( - derived_scenario_path.extension().string() + "." + - std::to_string(parameter_list.index())); + std::to_string(parameter_list.index()) + derived_scenario_path.extension().string()); derived_scenario.path = derived_scenario_path.string(); From b7e4b96c429e3e7a81b58681b124644ddc8ab249 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 17 Apr 2023 17:09:19 +0900 Subject: [PATCH 071/120] refactor --- .../openscenario_preprocessor.hpp | 1 - .../openscenario_preprocessor/package.xml | 38 +++++++++---------- 2 files changed, 19 insertions(+), 20 deletions(-) diff --git a/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp b/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp index 6b5ca3b836f..6263c158110 100644 --- a/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp +++ b/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp @@ -61,7 +61,6 @@ class Preprocessor boost::filesystem::path output_directory; }; - } // namespace openscenario_preprocessor #endif // OPENSCENARIO_PREPROCESSOR__OPENSCENARIO_PREPROCESSOR_HPP_ diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index dd7c018ec7d..57e1bb218a1 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -2,27 +2,27 @@ - openscenario_preprocessor - 0.6.7 - Example package for TIER IV OpenSCENARIO Interpreter - Kotaro Yoshimoto - Apache License 2.0 + openscenario_preprocessor + 0.6.7 + Example package for TIER IV OpenSCENARIO Interpreter + Kotaro Yoshimoto + Apache License 2.0 - ament_cmake_auto + ament_cmake_auto - openscenario_interpreter - openscenario_preprocessor_msgs - rclcpp - openscenario_utility + openscenario_interpreter + openscenario_preprocessor_msgs + rclcpp + openscenario_utility - ament_cmake_clang_format - ament_cmake_copyright - ament_cmake_gtest - ament_cmake_pep257 - ament_cmake_xmllint - ament_lint_auto + ament_cmake_clang_format + ament_cmake_copyright + ament_cmake_gtest + ament_cmake_pep257 + ament_cmake_xmllint + ament_lint_auto - - ament_cmake - + + ament_cmake + From 7e990e0caae7e52c99c96be1dac69f3fdb4164c1 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 17 Apr 2023 17:26:37 +0900 Subject: [PATCH 072/120] chore: fix indent of xml and xosc files --- .../Deterministic.DistributionRange.xosc | 22 +++++----- .../Deterministic.DistributionSet.xosc | 26 ++++++------ .../Deterministic.ValueSetDistribution.xosc | 28 ++++++------- .../scenario/Stochastic.Histogram.xosc | 40 +++++++++---------- .../Stochastic.NormalDistribution.xosc | 22 +++++----- .../Stochastic.PoissonDistribution.xosc | 22 +++++----- ...Stochastic.ProbabilityDistributionSet.xosc | 26 ++++++------ .../Stochastic.UniformDistribution.xosc | 22 +++++----- 8 files changed, 104 insertions(+), 104 deletions(-) diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc index c5487edf7c6..e66c305be01 100644 --- a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc +++ b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc @@ -1,14 +1,14 @@ - - - - - - - - - - - + + + + + + + + + + + diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc index 9ed2c9244cf..3da621c7659 100644 --- a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc +++ b/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc @@ -1,16 +1,16 @@ - - - - - - - - - - - - - + + + + + + + + + + + + + diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc b/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc index f81017b9d3b..2cdef8ff1f8 100644 --- a/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc +++ b/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc @@ -1,16 +1,16 @@ - - - - - - - - - - - - - - + + + + + + + + + + + + + + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc index ec43a3c1b99..134adfd9d6f 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc +++ b/test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc @@ -1,22 +1,22 @@ - + - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc index 5019af40009..4c09f113523 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc +++ b/test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc @@ -1,14 +1,14 @@ - - - - - - - - - - - + + + + + + + + + + + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc index a47f9f546ad..cbcad3c3226 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc +++ b/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc @@ -1,14 +1,14 @@ - - - - - - - - - - - + + + + + + + + + + + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc index db4329da7f2..0382e569c8b 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc +++ b/test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc @@ -1,16 +1,16 @@ - - - - - - - - - - - - - + + + + + + + + + + + + + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc index 70ef6d7a9db..72e59bd92cb 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc +++ b/test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc @@ -1,14 +1,14 @@ - - - - - - - - - - - + + + + + + + + + + + From 3bda669c18a99c80c20951203713b7f0e16837fd Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 17 Apr 2023 17:38:11 +0900 Subject: [PATCH 073/120] chore: delete confusing comments --- .../include/openscenario_utility/xml_validator.hpp | 8 -------- 1 file changed, 8 deletions(-) diff --git a/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp b/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp index a04e2fb2e60..6c846677578 100644 --- a/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp +++ b/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp @@ -30,27 +30,20 @@ class XMLValidator public: explicit XMLValidator(boost::filesystem::path xsd_file) : xsd_file(xsd_file) { - // Initialize Xerces library xercesc::XMLPlatformUtils::Initialize(); } ~XMLValidator() { - // Terminate Xerces library xercesc::XMLPlatformUtils::Terminate(); } - [[nodiscard]] bool validate(const boost::filesystem::path & xml_file) noexcept { try { - // Create a DOM parser xercesc::XercesDOMParser parser; - - // Load the XSD file parser.loadGrammar(xsd_file.string().c_str(), xercesc::Grammar::SchemaGrammarType, true); - // Set the validation scheme xercesc::ErrorHandler * error_handler = new xercesc::HandlerBase(); parser.setErrorHandler(error_handler); parser.setValidationScheme(xercesc::XercesDOMParser::Val_Auto); @@ -58,7 +51,6 @@ class XMLValidator parser.setDoSchema(true); parser.setValidationConstraintFatal(true); - // Parse the XML file parser.parse(xml_file.string().c_str()); int error_count = parser.getErrorCount(); From a5ba436f17ca700c1890a18f0ff7afc1039ea18c Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 17 Apr 2023 18:10:34 +0900 Subject: [PATCH 074/120] refactor(openscenario_interpreter): use std::size_t instead of size_t --- .../openscenario_interpreter/parameter_distribution.hpp | 4 ++-- .../openscenario_interpreter/syntax/deterministic.hpp | 4 ++-- .../syntax/deterministic_multi_parameter_distribution.hpp | 4 ++-- .../deterministic_single_parameter_distribution.hpp | 4 ++-- .../syntax/distribution_range.hpp | 4 ++-- .../openscenario_interpreter/syntax/distribution_set.hpp | 4 ++-- .../include/openscenario_interpreter/syntax/histogram.hpp | 2 +- .../syntax/normal_distribution.hpp | 2 +- .../syntax/parameter_value_distribution.hpp | 4 ++-- .../syntax/poisson_distribution.hpp | 2 +- .../syntax/probability_distribution_set.hpp | 2 +- .../openscenario_interpreter/syntax/stochastic.hpp | 4 ++-- .../syntax/stochastic_distribution.hpp | 2 +- .../syntax/uniform_distribution.hpp | 2 +- .../syntax/value_set_distribution.hpp | 4 ++-- .../openscenario_interpreter/src/syntax/deterministic.cpp | 8 ++++---- .../syntax/deterministic_multi_parameter_distribution.cpp | 4 ++-- .../deterministic_single_parameter_distribution.cpp | 6 +++--- .../src/syntax/distribution_range.cpp | 4 ++-- .../src/syntax/distribution_set.cpp | 4 ++-- .../openscenario_interpreter/src/syntax/histogram.cpp | 2 +- .../src/syntax/normal_distribution.cpp | 2 +- .../src/syntax/parameter_value_distribution.cpp | 6 +++--- .../src/syntax/poisson_distribution.cpp | 2 +- .../src/syntax/probability_distribution_set.cpp | 6 +++--- .../openscenario_interpreter/src/syntax/stochastic.cpp | 4 ++-- .../src/syntax/stochastic_distribution.cpp | 2 +- .../src/syntax/uniform_distribution.cpp | 2 +- .../src/syntax/value_set_distribution.cpp | 4 ++-- 29 files changed, 52 insertions(+), 52 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp index 1045b1d511c..a499e9ed6ea 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -33,10 +33,10 @@ using SingleUnnamedParameterDistribution = std::vector; struct ParallelDerivableParameterDistributionBase { virtual auto derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList = 0; - virtual auto getNumberOfDeriveScenarios() const -> size_t + virtual auto getNumberOfDeriveScenarios() const -> std::size_t { throw Error("getNumberOfDeriveScenarios() is not implemented"); } diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp index 0cf8840f686..c93363c5c35 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp @@ -41,10 +41,10 @@ struct Deterministic : public ParameterDistributionContainer auto derive() -> ParameterDistribution override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; - auto getNumberOfDeriveScenarios() const -> size_t override; + auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp index f46d5a38309..a0640b4927b 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp @@ -39,10 +39,10 @@ struct DeterministicMultiParameterDistribution : public DeterministicMultiParame auto derive() -> ParameterDistribution override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; - auto getNumberOfDeriveScenarios() const -> size_t override; + auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index d7588b0b02f..3627271fea2 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -43,10 +43,10 @@ struct DeterministicSingleParameterDistribution auto derive() -> ParameterDistribution override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; - auto getNumberOfDeriveScenarios() const -> size_t override; + auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index 8815e1c2673..86a3ca9c24a 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -44,10 +44,10 @@ struct DistributionRange : private Scope, public ComplexType, public SingleParam auto derive() -> SingleUnnamedParameterDistribution override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; - auto getNumberOfDeriveScenarios() const -> size_t override; + auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index b8beed33477..cb701330b13 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -40,10 +40,10 @@ struct DistributionSet : private Scope, public ComplexType, public SingleParamet auto derive() -> SingleUnnamedParameterDistribution override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; - auto getNumberOfDeriveScenarios() const -> size_t override; + auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index e11e2db24ec..84be1a94870 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -62,7 +62,7 @@ struct Histogram : public ComplexType, private Scope, public StochasticParameter auto derive() -> Object override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp index b62c705b1d4..199135dfb74 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp @@ -54,7 +54,7 @@ struct NormalDistribution : public ComplexType, auto derive() -> Object override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp index a1e32684229..7d0dfb24dce 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp @@ -41,10 +41,10 @@ struct ParameterValueDistribution : public DistributionDefinition, auto derive() -> ParameterDistribution override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; - auto getNumberOfDeriveScenarios() const -> size_t override; + auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index 5497ac73fdf..e91dd69dcc9 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -49,7 +49,7 @@ struct PoissonDistribution : public ComplexType, auto derive() -> Object override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index 86e74ea447b..b37fe26b7e7 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -59,7 +59,7 @@ struct ProbabilityDistributionSet : public ComplexType, auto derive() -> Object override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp index cca4dbb0ea7..6a4357b511b 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp @@ -51,10 +51,10 @@ struct Stochastic : public ComplexType, public ParameterDistributionContainer, p auto derive() -> ParameterDistribution override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; - auto getNumberOfDeriveScenarios() const -> size_t override { return number_of_test_runs; } + auto getNumberOfDeriveScenarios() const -> std::size_t override { return number_of_test_runs; } }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp index 7ab17f62762..58bc293239b 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp @@ -43,7 +43,7 @@ struct StochasticDistribution : public StochasticDistributionType, auto derive() -> Object override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index 663f4ce37aa..dfdcefddc85 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -45,7 +45,7 @@ struct UniformDistribution : public ComplexType, auto derive() -> Object override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; }; } // namespace syntax diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp index 617074bb4b5..23695f40203 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp @@ -40,10 +40,10 @@ struct ValueSetDistribution : public Scope, public MultiParameterDistributionBas auto derive() -> ParameterDistribution override; - auto derive(size_t local_index, size_t local_size, size_t global_index, size_t global_size) + auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList override; - auto getNumberOfDeriveScenarios() const -> size_t override; + auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp index 82b7ddf4f1f..52e44d763a0 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp @@ -38,7 +38,7 @@ auto Deterministic::derive() -> ParameterDistribution } auto Deterministic::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList { auto child = std::next(deterministic_parameter_distributions.begin(), std::floor(local_index / local_size)); @@ -51,13 +51,13 @@ auto Deterministic::derive( (DeterministicParameterDistribution &)*child); } -auto Deterministic::getNumberOfDeriveScenarios() const -> size_t +auto Deterministic::getNumberOfDeriveScenarios() const -> std::size_t { return std::accumulate( deterministic_parameter_distributions.begin(), deterministic_parameter_distributions.end(), 1, - [](size_t pre_result, auto distribution) { + [](std::size_t pre_result, auto distribution) { return pre_result * - apply( + apply( [](auto & distribution) { return distribution.getNumberOfDeriveScenarios(); }, distribution); }); diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp index e68c2bcfc11..e206f510777 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp @@ -31,13 +31,13 @@ auto DeterministicMultiParameterDistribution::derive() -> ParameterDistribution } auto DeterministicMultiParameterDistribution::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList { return DeterministicMultiParameterDistributionType::derive( local_index, local_size, global_index, global_size); } -auto DeterministicMultiParameterDistribution::getNumberOfDeriveScenarios() const -> size_t +auto DeterministicMultiParameterDistribution::getNumberOfDeriveScenarios() const -> std::size_t { return DeterministicMultiParameterDistributionType::getNumberOfDeriveScenarios(); } diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp index 06ac15a5243..08ad22d201d 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp @@ -42,7 +42,7 @@ auto DeterministicSingleParameterDistribution::derive() -> ParameterDistribution } auto DeterministicSingleParameterDistribution::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList { return { {parameter_name, apply( @@ -55,9 +55,9 @@ auto DeterministicSingleParameterDistribution::derive( ->second}}; } -auto DeterministicSingleParameterDistribution::getNumberOfDeriveScenarios() const -> size_t +auto DeterministicSingleParameterDistribution::getNumberOfDeriveScenarios() const -> std::size_t { - return apply( + return apply( [](auto & unnamed_distribution) { return unnamed_distribution.getNumberOfDeriveScenarios(); }, (DeterministicSingleParameterDistributionType &)*this); } diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp index 661747d9dd8..79c0f84bfd2 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp @@ -37,12 +37,12 @@ auto DistributionRange::derive() -> SingleUnnamedParameterDistribution } auto DistributionRange::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList { return ParameterList({{"", make(range.lower_limit + step_width * local_index)}}); } -auto DistributionRange::getNumberOfDeriveScenarios() const -> size_t +auto DistributionRange::getNumberOfDeriveScenarios() const -> std::size_t { return int((range.upper_limit - range.lower_limit) / step_width) + 1; } diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp index c9abd43be6c..c6e1ac27e79 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp @@ -34,11 +34,11 @@ auto DistributionSet::derive() -> SingleUnnamedParameterDistribution } auto DistributionSet::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList { return ParameterList({{"", make(std::next(elements.begin(), local_index)->value)}}); } -auto DistributionSet::getNumberOfDeriveScenarios() const -> size_t { return std::size(elements); } +auto DistributionSet::getNumberOfDeriveScenarios() const -> std::size_t { return std::size(elements); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp index 9b7d3ee589a..fcffba8c99d 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp @@ -31,7 +31,7 @@ Histogram::Histogram(const pugi::xml_node & node, openscenario_interpreter::Scop auto Histogram::derive() -> Object { return make(distribute(random_engine)); } auto Histogram::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList { return ParameterList({{"", make(distribute(random_engine))}}); } diff --git a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp index 4ea4362ae62..977ade7e5a9 100644 --- a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp @@ -32,7 +32,7 @@ NormalDistribution::NormalDistribution( auto NormalDistribution::derive() -> Object { return make(distribute(random_engine)); } auto NormalDistribution::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList { return ParameterList({{"", make(distribute(random_engine))}}); } diff --git a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp index ff21c96e2d4..60e640667bf 100644 --- a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp @@ -31,15 +31,15 @@ auto ParameterValueDistribution::derive() -> ParameterDistribution [](auto & distribution) { return distribution.derive(); }, *this); } -auto ParameterValueDistribution::getNumberOfDeriveScenarios() const -> size_t +auto ParameterValueDistribution::getNumberOfDeriveScenarios() const -> std::size_t { - return apply( + return apply( [](auto & distribution) { return distribution.getNumberOfDeriveScenarios(); }, (DistributionDefinition &)*this); } auto ParameterValueDistribution::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList { return apply( [&](auto & distribution) { diff --git a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp index 22553b2fa85..bb15d4d5d6a 100644 --- a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp @@ -34,7 +34,7 @@ auto PoissonDistribution::derive() -> Object } ParameterList PoissonDistribution::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) { return ParameterList({{"", make(range.evaluate(distribute(random_engine)))}}); } diff --git a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp index 389d94fd74b..fb788028dc7 100644 --- a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp @@ -38,14 +38,14 @@ ProbabilityDistributionSet::ProbabilityDistributionSet( auto ProbabilityDistributionSet::derive() -> Object { - size_t index = distribute(random_engine); + std::size_t index = distribute(random_engine); return make(elements.at(index).value); } auto ProbabilityDistributionSet::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList { - size_t index = distribute(random_engine); + std::size_t index = distribute(random_engine); return ParameterList{{"", make(elements.at(index).value)}}; } } // namespace syntax diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp index 44c60b45c61..9c71414bb82 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp @@ -40,7 +40,7 @@ Stochastic::Stochastic(const pugi::xml_node & node, Scope & scope) auto Stochastic::derive() -> ParameterDistribution { ParameterDistribution distribution; - for (size_t i = 0; i < number_of_test_runs; i++) { + for (std::size_t i = 0; i < number_of_test_runs; i++) { ParameterListSharedPtr parameter_list = std::make_shared(); for (auto & stochastic_distribution : stochastic_distributions) { auto derived = stochastic_distribution.derive(); @@ -52,7 +52,7 @@ auto Stochastic::derive() -> ParameterDistribution } auto Stochastic::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList { // update random_engine random_engine.seed(random_seed); diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp index b56ce3cd806..2757fe436ce 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp @@ -32,7 +32,7 @@ auto StochasticDistribution::derive() -> Object } auto StochasticDistribution::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList { return { {parameter_name, make(apply( diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index ebf5f9577c9..578b3d650fd 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -30,7 +30,7 @@ UniformDistribution::UniformDistribution( auto UniformDistribution::derive() -> Object { return make(distribute(random_engine)); } auto UniformDistribution::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList { return ParameterList({{"", make(distribute(random_engine))}}); } diff --git a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp index 1c05304bbfc..4489fb5a0ad 100644 --- a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp @@ -36,12 +36,12 @@ auto ValueSetDistribution::derive() -> ParameterDistribution } auto ValueSetDistribution::derive( - size_t local_index, size_t local_size, size_t global_index, size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList { return *(std::next(parameter_value_sets.begin(), local_index)->evaluate()); } -auto ValueSetDistribution::getNumberOfDeriveScenarios() const -> size_t +auto ValueSetDistribution::getNumberOfDeriveScenarios() const -> std::size_t { return std::size(parameter_value_sets); } From 7da09eb5ad3f7d5a9411d48573fff511ee665fea Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 17 Apr 2023 18:20:20 +0900 Subject: [PATCH 075/120] refactor(xml_validator): use modern C++ --- .../openscenario_utility/xml_validator.hpp | 15 +++++---------- 1 file changed, 5 insertions(+), 10 deletions(-) diff --git a/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp b/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp index 6c846677578..bce38920596 100644 --- a/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp +++ b/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp @@ -33,19 +33,16 @@ class XMLValidator xercesc::XMLPlatformUtils::Initialize(); } - ~XMLValidator() - { - xercesc::XMLPlatformUtils::Terminate(); - } + ~XMLValidator() { xercesc::XMLPlatformUtils::Terminate(); } [[nodiscard]] bool validate(const boost::filesystem::path & xml_file) noexcept { try { - xercesc::XercesDOMParser parser; + auto parser = xercesc::XercesDOMParser(); parser.loadGrammar(xsd_file.string().c_str(), xercesc::Grammar::SchemaGrammarType, true); - xercesc::ErrorHandler * error_handler = new xercesc::HandlerBase(); - parser.setErrorHandler(error_handler); + auto error_handler = std::make_unique(); + parser.setErrorHandler(error_handler.get()); parser.setValidationScheme(xercesc::XercesDOMParser::Val_Auto); parser.setDoNamespaces(true); parser.setDoSchema(true); @@ -53,9 +50,7 @@ class XMLValidator parser.parse(xml_file.string().c_str()); - int error_count = parser.getErrorCount(); - delete error_handler; - return error_count == 0; + return parser.getErrorCount() == 0; } catch (const xercesc::XMLException & ex) { std::cerr << "Error: " << ex.getMessage() << std::endl; return false; From 8d61899871fff0a5ad91d8cc4d8beb24a1c999e7 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 18 Apr 2023 04:41:04 +0900 Subject: [PATCH 076/120] chore: apply linter --- .../openscenario_interpreter/parameter_distribution.hpp | 4 ++-- .../openscenario_interpreter/syntax/deterministic.hpp | 5 +++-- .../syntax/deterministic_multi_parameter_distribution.hpp | 5 +++-- .../deterministic_single_parameter_distribution.hpp | 5 +++-- .../syntax/distribution_range.hpp | 5 +++-- .../openscenario_interpreter/syntax/distribution_set.hpp | 5 +++-- .../include/openscenario_interpreter/syntax/histogram.hpp | 5 +++-- .../syntax/normal_distribution.hpp | 5 +++-- .../syntax/parameter_value_distribution.hpp | 5 +++-- .../syntax/poisson_distribution.hpp | 5 +++-- .../syntax/probability_distribution_set.hpp | 5 +++-- .../openscenario_interpreter/syntax/stochastic.hpp | 5 +++-- .../syntax/stochastic_distribution.hpp | 5 +++-- .../syntax/uniform_distribution.hpp | 5 +++-- .../syntax/value_set_distribution.hpp | 5 +++-- .../openscenario_interpreter/src/syntax/deterministic.cpp | 3 ++- .../syntax/deterministic_multi_parameter_distribution.cpp | 3 ++- .../deterministic_single_parameter_distribution.cpp | 3 ++- .../src/syntax/distribution_range.cpp | 3 ++- .../src/syntax/distribution_set.cpp | 8 ++++++-- .../openscenario_interpreter/src/syntax/histogram.cpp | 3 ++- .../src/syntax/normal_distribution.cpp | 3 ++- .../src/syntax/parameter_value_distribution.cpp | 3 ++- .../src/syntax/poisson_distribution.cpp | 3 ++- .../src/syntax/probability_distribution_set.cpp | 3 ++- .../openscenario_interpreter/src/syntax/stochastic.cpp | 3 ++- .../src/syntax/stochastic_distribution.cpp | 3 ++- .../src/syntax/uniform_distribution.cpp | 3 ++- .../src/syntax/value_set_distribution.cpp | 3 ++- 29 files changed, 76 insertions(+), 45 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp index a499e9ed6ea..475a9018e5f 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -33,8 +33,8 @@ using SingleUnnamedParameterDistribution = std::vector; struct ParallelDerivableParameterDistributionBase { virtual auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList = 0; + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList = 0; virtual auto getNumberOfDeriveScenarios() const -> std::size_t { diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp index c93363c5c35..7e13affd30a 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp @@ -41,8 +41,9 @@ struct Deterministic : public ParameterDistributionContainer auto derive() -> ParameterDistribution override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; auto getNumberOfDeriveScenarios() const -> std::size_t override; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp index a0640b4927b..7e00a82cc47 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp @@ -39,8 +39,9 @@ struct DeterministicMultiParameterDistribution : public DeterministicMultiParame auto derive() -> ParameterDistribution override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; auto getNumberOfDeriveScenarios() const -> std::size_t override; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index 3627271fea2..124eb0936d3 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -43,8 +43,9 @@ struct DeterministicSingleParameterDistribution auto derive() -> ParameterDistribution override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; auto getNumberOfDeriveScenarios() const -> std::size_t override; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index 86a3ca9c24a..dfcbfd7fe56 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -44,8 +44,9 @@ struct DistributionRange : private Scope, public ComplexType, public SingleParam auto derive() -> SingleUnnamedParameterDistribution override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; auto getNumberOfDeriveScenarios() const -> std::size_t override; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index cb701330b13..3e7a5079175 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -40,8 +40,9 @@ struct DistributionSet : private Scope, public ComplexType, public SingleParamet auto derive() -> SingleUnnamedParameterDistribution override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; auto getNumberOfDeriveScenarios() const -> std::size_t override; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index 84be1a94870..4631a218cbb 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -62,8 +62,9 @@ struct Histogram : public ComplexType, private Scope, public StochasticParameter auto derive() -> Object override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp index 199135dfb74..da6d2685614 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp @@ -54,8 +54,9 @@ struct NormalDistribution : public ComplexType, auto derive() -> Object override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp index 7d0dfb24dce..828df2c4ace 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp @@ -41,8 +41,9 @@ struct ParameterValueDistribution : public DistributionDefinition, auto derive() -> ParameterDistribution override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; auto getNumberOfDeriveScenarios() const -> std::size_t override; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index e91dd69dcc9..32b4ff8faa6 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -49,8 +49,9 @@ struct PoissonDistribution : public ComplexType, auto derive() -> Object override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index b37fe26b7e7..bc0a3cafa96 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -59,8 +59,9 @@ struct ProbabilityDistributionSet : public ComplexType, auto derive() -> Object override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp index 6a4357b511b..83e74963152 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp @@ -51,8 +51,9 @@ struct Stochastic : public ComplexType, public ParameterDistributionContainer, p auto derive() -> ParameterDistribution override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; auto getNumberOfDeriveScenarios() const -> std::size_t override { return number_of_test_runs; } }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp index 58bc293239b..9ef62382178 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp @@ -43,8 +43,9 @@ struct StochasticDistribution : public StochasticDistributionType, auto derive() -> Object override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index dfdcefddc85..8637b94d27d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -45,8 +45,9 @@ struct UniformDistribution : public ComplexType, auto derive() -> Object override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp index 23695f40203..11a6dfcf986 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp @@ -40,8 +40,9 @@ struct ValueSetDistribution : public Scope, public MultiParameterDistributionBas auto derive() -> ParameterDistribution override; - auto derive(std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) - -> ParameterList override; + auto derive( + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList override; auto getNumberOfDeriveScenarios() const -> std::size_t override; }; diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp index 52e44d763a0..376774e8bfe 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp @@ -38,7 +38,8 @@ auto Deterministic::derive() -> ParameterDistribution } auto Deterministic::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList { auto child = std::next(deterministic_parameter_distributions.begin(), std::floor(local_index / local_size)); diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp index e206f510777..a8bef18d055 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp @@ -31,7 +31,8 @@ auto DeterministicMultiParameterDistribution::derive() -> ParameterDistribution } auto DeterministicMultiParameterDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList { return DeterministicMultiParameterDistributionType::derive( local_index, local_size, global_index, global_size); diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp index 08ad22d201d..ac420ce89cc 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp @@ -42,7 +42,8 @@ auto DeterministicSingleParameterDistribution::derive() -> ParameterDistribution } auto DeterministicSingleParameterDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList { return { {parameter_name, apply( diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp index 79c0f84bfd2..a6c9ac0e6c1 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp @@ -37,7 +37,8 @@ auto DistributionRange::derive() -> SingleUnnamedParameterDistribution } auto DistributionRange::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList { return ParameterList({{"", make(range.lower_limit + step_width * local_index)}}); } diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp index c6e1ac27e79..9c11257ae62 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp @@ -34,11 +34,15 @@ auto DistributionSet::derive() -> SingleUnnamedParameterDistribution } auto DistributionSet::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList { return ParameterList({{"", make(std::next(elements.begin(), local_index)->value)}}); } -auto DistributionSet::getNumberOfDeriveScenarios() const -> std::size_t { return std::size(elements); } +auto DistributionSet::getNumberOfDeriveScenarios() const -> std::size_t +{ + return std::size(elements); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp index fcffba8c99d..593bf2bb6d7 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp @@ -31,7 +31,8 @@ Histogram::Histogram(const pugi::xml_node & node, openscenario_interpreter::Scop auto Histogram::derive() -> Object { return make(distribute(random_engine)); } auto Histogram::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList { return ParameterList({{"", make(distribute(random_engine))}}); } diff --git a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp index 977ade7e5a9..d17ddb88189 100644 --- a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp @@ -32,7 +32,8 @@ NormalDistribution::NormalDistribution( auto NormalDistribution::derive() -> Object { return make(distribute(random_engine)); } auto NormalDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList { return ParameterList({{"", make(distribute(random_engine))}}); } diff --git a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp index 60e640667bf..4388e37e9c8 100644 --- a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp @@ -39,7 +39,8 @@ auto ParameterValueDistribution::getNumberOfDeriveScenarios() const -> std::size } auto ParameterValueDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList { return apply( [&](auto & distribution) { diff --git a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp index bb15d4d5d6a..d0df2cce5cc 100644 --- a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp @@ -34,7 +34,8 @@ auto PoissonDistribution::derive() -> Object } ParameterList PoissonDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) { return ParameterList({{"", make(range.evaluate(distribute(random_engine)))}}); } diff --git a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp index fb788028dc7..11564c55f54 100644 --- a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp @@ -43,7 +43,8 @@ auto ProbabilityDistributionSet::derive() -> Object } auto ProbabilityDistributionSet::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList { std::size_t index = distribute(random_engine); return ParameterList{{"", make(elements.at(index).value)}}; diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp index 9c71414bb82..0829d2027ba 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp @@ -52,7 +52,8 @@ auto Stochastic::derive() -> ParameterDistribution } auto Stochastic::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList { // update random_engine random_engine.seed(random_seed); diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp index 2757fe436ce..3c8b051c433 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp @@ -32,7 +32,8 @@ auto StochasticDistribution::derive() -> Object } auto StochasticDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList { return { {parameter_name, make(apply( diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index 578b3d650fd..e273ffb28d6 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -30,7 +30,8 @@ UniformDistribution::UniformDistribution( auto UniformDistribution::derive() -> Object { return make(distribute(random_engine)); } auto UniformDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList { return ParameterList({{"", make(distribute(random_engine))}}); } diff --git a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp index 4489fb5a0ad..37a432f81c1 100644 --- a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp @@ -36,7 +36,8 @@ auto ValueSetDistribution::derive() -> ParameterDistribution } auto ValueSetDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, std::size_t global_size) -> ParameterList + std::size_t local_index, std::size_t local_size, std::size_t global_index, + std::size_t global_size) -> ParameterList { return *(std::next(parameter_value_sets.begin(), local_index)->evaluate()); } From 0dc850c69deac0ea3f0d840c6df442efe0cea6c0 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 18 Apr 2023 05:01:01 +0900 Subject: [PATCH 077/120] chore: apply linter --- .../openscenario_interpreter/syntax/deterministic.hpp | 6 +++--- .../syntax/deterministic_multi_parameter_distribution.hpp | 6 +++--- .../deterministic_multi_parameter_distribution_type.hpp | 6 +++--- .../syntax/deterministic_parameter_distribution.hpp | 6 +++--- .../syntax/deterministic_single_parameter_distribution.hpp | 6 +++--- .../deterministic_single_parameter_distribution_type.hpp | 6 +++--- .../syntax/distribution_definition.hpp | 6 +++--- .../openscenario_interpreter/syntax/distribution_set.hpp | 6 +++--- .../include/openscenario_interpreter/syntax/histogram.hpp | 6 +++--- .../openscenario_interpreter/syntax/histogram_bin.hpp | 6 +++--- .../openscenario_interpreter/syntax/normal_distribution.hpp | 6 +++--- .../syntax/parameter_value_distribution.hpp | 6 +++--- .../openscenario_interpreter/syntax/parameter_value_set.hpp | 6 +++--- .../syntax/poisson_distribution.hpp | 6 +++--- .../syntax/probability_distribution_set.hpp | 6 +++--- .../syntax/probability_distribution_set_element.hpp | 6 +++--- .../include/openscenario_interpreter/syntax/stochastic.hpp | 6 +++--- .../syntax/stochastic_distribution.hpp | 6 +++--- .../syntax/stochastic_distribution_type.hpp | 6 +++--- .../syntax/uniform_distribution.hpp | 6 +++--- .../syntax/value_set_distribution.hpp | 6 +++--- openscenario/openscenario_preprocessor/package.xml | 3 +-- openscenario/openscenario_utility/package.xml | 6 +++--- 23 files changed, 67 insertions(+), 68 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp index 7e13affd30a..bcd395a407c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__DETERMINISTIC_HPP_ -#define OPENSCENARIO_INTERPRETER__DETERMINISTIC_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_HPP_ #include #include @@ -49,4 +49,4 @@ struct Deterministic : public ParameterDistributionContainer }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__DETERMINISTIC_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp index 7e00a82cc47..eb43dc1215e 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__DETERMINISTIC_MULTI_PARAMETER_DISTRIBUTION_HPP_ -#define OPENSCENARIO_INTERPRETER__DETERMINISTIC_MULTI_PARAMETER_DISTRIBUTION_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_MULTI_PARAMETER_DISTRIBUTION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_MULTI_PARAMETER_DISTRIBUTION_HPP_ #include #include @@ -47,4 +47,4 @@ struct DeterministicMultiParameterDistribution : public DeterministicMultiParame }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__DETERMINISTIC_MULTI_PARAMETER_DISTRIBUTION_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_MULTI_PARAMETER_DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution_type.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution_type.hpp index a51f13be031..7449dbde838 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution_type.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution_type.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__DETERMINISTIC_MULTI_PARAMETER_DISTRIBUTION_TYPE_HPP_ -#define OPENSCENARIO_INTERPRETER__DETERMINISTIC_MULTI_PARAMETER_DISTRIBUTION_TYPE_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_MULTI_PARAMETER_DISTRIBUTION_TYPE_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_MULTI_PARAMETER_DISTRIBUTION_TYPE_HPP_ #include #include @@ -39,4 +39,4 @@ struct DeterministicMultiParameterDistributionType : public ValueSetDistribution } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__DETERMINISTIC_MULTI_PARAMETER_DISTRIBUTION_TYPE_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_MULTI_PARAMETER_DISTRIBUTION_TYPE_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_parameter_distribution.hpp index c81226d3886..abc81721d22 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_parameter_distribution.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__DETERMINISTIC_PARAMETER_DISTRIBUTION_HPP_ -#define OPENSCENARIO_INTERPRETER__DETERMINISTIC_PARAMETER_DISTRIBUTION_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_PARAMETER_DISTRIBUTION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_PARAMETER_DISTRIBUTION_HPP_ #include #include @@ -48,4 +48,4 @@ DEFINE_LAZY_VISITOR( ); } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__DETERMINISTIC_PARAMETER_DISTRIBUTION_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_PARAMETER_DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index 124eb0936d3..4d06f2efb83 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_HPP_ -#define OPENSCENARIO_INTERPRETER__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_HPP_ #include #include @@ -51,4 +51,4 @@ struct DeterministicSingleParameterDistribution }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp index 081c003e6f8..1b091c5807e 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_TYPE_HPP_ -#define OPENSCENARIO_INTERPRETER__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_TYPE_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_TYPE_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_TYPE_HPP_ #include #include @@ -50,4 +50,4 @@ DEFINE_LAZY_VISITOR( ); } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_TYPE_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__DETERMINISTIC_SINGLE_PARAMETER_DISTRIBUTION_TYPE_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_definition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_definition.hpp index 6fcba2c500f..576fb1dbd12 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_definition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_definition.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__DISTRIBUTION_DEFINITION_HPP_ -#define OPENSCENARIO_INTERPRETER__DISTRIBUTION_DEFINITION_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__DISTRIBUTION_DEFINITION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__DISTRIBUTION_DEFINITION_HPP_ #include #include @@ -47,4 +47,4 @@ DEFINE_LAZY_VISITOR( } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__DISTRIBUTION_DEFINITION_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__DISTRIBUTION_DEFINITION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index 3e7a5079175..4bdc92c2ae4 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__DISTRIBUTION_SET_HPP_ -#define OPENSCENARIO_INTERPRETER__DISTRIBUTION_SET_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__DISTRIBUTION_SET_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__DISTRIBUTION_SET_HPP_ #include #include @@ -48,4 +48,4 @@ struct DistributionSet : private Scope, public ComplexType, public SingleParamet }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__DISTRIBUTION_SET_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__DISTRIBUTION_SET_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index 4631a218cbb..84db5fd71f5 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__HISTOGRAM_HPP_ -#define OPENSCENARIO_INTERPRETER__HISTOGRAM_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__HISTOGRAM_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__HISTOGRAM_HPP_ #include #include @@ -68,4 +68,4 @@ struct Histogram : public ComplexType, private Scope, public StochasticParameter }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__HISTOGRAM_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__HISTOGRAM_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram_bin.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram_bin.hpp index 19e65a4b6d5..218880763ab 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram_bin.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram_bin.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__HISTOGRAM_BIN_HPP_ -#define OPENSCENARIO_INTERPRETER__HISTOGRAM_BIN_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__HISTOGRAM_BIN_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__HISTOGRAM_BIN_HPP_ #include #include @@ -43,4 +43,4 @@ struct HistogramBin : public ComplexType }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__HISTOGRAM_BIN_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__HISTOGRAM_BIN_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp index da6d2685614..352b2f7a928 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__NORMAL_DISTRIBUTION_HPP_ -#define OPENSCENARIO_INTERPRETER__NORMAL_DISTRIBUTION_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__NORMAL_DISTRIBUTION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__NORMAL_DISTRIBUTION_HPP_ #include #include @@ -60,4 +60,4 @@ struct NormalDistribution : public ComplexType, }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__NORMAL_DISTRIBUTION_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__NORMAL_DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp index 828df2c4ace..adfa9b7d505 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__PARAMETER_VALUE_DISTRIBUTION_HPP_ -#define OPENSCENARIO_INTERPRETER__PARAMETER_VALUE_DISTRIBUTION_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__PARAMETER_VALUE_DISTRIBUTION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__PARAMETER_VALUE_DISTRIBUTION_HPP_ #include #include @@ -49,4 +49,4 @@ struct ParameterValueDistribution : public DistributionDefinition, }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__PARAMETER_VALUE_DISTRIBUTION_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__PARAMETER_VALUE_DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp index 61803c3571d..63b7f65d938 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__PARAMETER_VALUE_SET_HPP_ -#define OPENSCENARIO_INTERPRETER__PARAMETER_VALUE_SET_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__PARAMETER_VALUE_SET_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__PARAMETER_VALUE_SET_HPP_ #include @@ -40,4 +40,4 @@ struct ParameterValueSet : private Scope }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__PARAMETER_VALUE_SET_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__PARAMETER_VALUE_SET_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index 32b4ff8faa6..02cc5950bed 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__POISSON_DISTRIBUTION_HPP_ -#define OPENSCENARIO_INTERPRETER__POISSON_DISTRIBUTION_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__POISSON_DISTRIBUTION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__POISSON_DISTRIBUTION_HPP_ #include #include @@ -55,4 +55,4 @@ struct PoissonDistribution : public ComplexType, }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__POISSON_DISTRIBUTION_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__POISSON_DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index bc0a3cafa96..2c9de30ff34 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__PROBABILITY_DISTRIBUTION_SET_HPP_ -#define OPENSCENARIO_INTERPRETER__PROBABILITY_DISTRIBUTION_SET_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__PROBABILITY_DISTRIBUTION_SET_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__PROBABILITY_DISTRIBUTION_SET_HPP_ #include #include @@ -65,4 +65,4 @@ struct ProbabilityDistributionSet : public ComplexType, }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__PROBABILITY_DISTRIBUTION_SET_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__PROBABILITY_DISTRIBUTION_SET_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set_element.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set_element.hpp index cc00506623e..b9d23e1a9d9 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set_element.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set_element.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__PROBABILITY_DISTRIBUTION_SET_ELEMENT_HPP_ -#define OPENSCENARIO_INTERPRETER__PROBABILITY_DISTRIBUTION_SET_ELEMENT_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__PROBABILITY_DISTRIBUTION_SET_ELEMENT_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__PROBABILITY_DISTRIBUTION_SET_ELEMENT_HPP_ #include #include @@ -41,4 +41,4 @@ struct ProbabilityDistributionSetElement : public ComplexType }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__PROBABILITY_DISTRIBUTION_SET_ELEMENT_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__PROBABILITY_DISTRIBUTION_SET_ELEMENT_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp index 83e74963152..5ca321ab594 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__STOCHASTIC_HPP_ -#define OPENSCENARIO_INTERPRETER__STOCHASTIC_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__STOCHASTIC_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__STOCHASTIC_HPP_ #include #include @@ -59,4 +59,4 @@ struct Stochastic : public ComplexType, public ParameterDistributionContainer, p }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__STOCHASTIC_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__STOCHASTIC_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp index 9ef62382178..7842c6289e3 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__STOCHASTIC_DISTRIBUTION_HPP_ -#define OPENSCENARIO_INTERPRETER__STOCHASTIC_DISTRIBUTION_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__STOCHASTIC_DISTRIBUTION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__STOCHASTIC_DISTRIBUTION_HPP_ #include #include @@ -49,4 +49,4 @@ struct StochasticDistribution : public StochasticDistributionType, }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__STOCHASTIC_DISTRIBUTION_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__STOCHASTIC_DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp index 3b7543e79aa..0761e1e78bf 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__STOCHASTIC_DISTRIBUTION_TYPE_HPP_ -#define OPENSCENARIO_INTERPRETER__STOCHASTIC_DISTRIBUTION_TYPE_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__STOCHASTIC_DISTRIBUTION_TYPE_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__STOCHASTIC_DISTRIBUTION_TYPE_HPP_ #include #include @@ -58,4 +58,4 @@ DEFINE_LAZY_VISITOR( ); } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__STOCHASTIC_DISTRIBUTION_TYPE_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__STOCHASTIC_DISTRIBUTION_TYPE_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index 8637b94d27d..de818528020 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__UNIFORM_DISTRIBUTION_HPP_ -#define OPENSCENARIO_INTERPRETER__UNIFORM_DISTRIBUTION_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__UNIFORM_DISTRIBUTION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__UNIFORM_DISTRIBUTION_HPP_ #include #include @@ -51,4 +51,4 @@ struct UniformDistribution : public ComplexType, }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__UNIFORM_DISTRIBUTION_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__UNIFORM_DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp index 11a6dfcf986..02b6f8242d1 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_INTERPRETER__VALUE_SET_DISTRIBUTION_HPP_ -#define OPENSCENARIO_INTERPRETER__VALUE_SET_DISTRIBUTION_HPP_ +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__VALUE_SET_DISTRIBUTION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__VALUE_SET_DISTRIBUTION_HPP_ #include #include @@ -48,4 +48,4 @@ struct ValueSetDistribution : public Scope, public MultiParameterDistributionBas }; } // namespace syntax } // namespace openscenario_interpreter -#endif // OPENSCENARIO_INTERPRETER__VALUE_SET_DISTRIBUTION_HPP_ +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__VALUE_SET_DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 57e1bb218a1..6c5983fee5c 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -1,6 +1,5 @@ - openscenario_preprocessor 0.6.7 @@ -12,8 +11,8 @@ openscenario_interpreter openscenario_preprocessor_msgs - rclcpp openscenario_utility + rclcpp ament_cmake_clang_format ament_cmake_copyright diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 14ef860e8b7..c6bf99626ce 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -9,13 +9,13 @@ ament_cmake ament_cmake_python - rclcpp - xerces - python3-numpy python3-xmlschema python3-yaml + rclcpp rclpy + xerces + ament_cmake From 67bfc284b91ce3b3ac5fa2b76a80d2ad8d788798 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 20 Apr 2023 17:34:45 +0900 Subject: [PATCH 078/120] apply yamasaki-san's patch --- .../syntax/user_defined_value_condition.cpp | 10 +- .../openscenario_preprocessor/CMakeLists.txt | 17 +- .../openscenario_preprocessor.hpp | 31 +- .../openscenario_preprocessor/package.xml | 3 +- .../src/openscenario_preprocessor.cpp | 94 +- .../src/openscenario_preprocessor_node.cpp | 29 +- .../openscenario_utility/CMakeLists.txt | 7 - openscenario/openscenario_utility/package.xml | 1 - .../openscenario_validator/.gitignore | 1 + .../openscenario_validator/CMakeLists.txt | 21 + .../configure/OpenSCENARIO-1.2.xsd | 2419 +++++++++++++++++ .../configure/schema.cpp | 20 + .../include/openscenario_validator/schema.hpp | 20 + .../openscenario_validator/validator.hpp} | 66 +- .../openscenario_validator/package.xml | 15 + .../openscenario_validator/src/validator.cpp | 35 + 16 files changed, 2656 insertions(+), 133 deletions(-) create mode 100644 openscenario/openscenario_validator/.gitignore create mode 100644 openscenario/openscenario_validator/CMakeLists.txt create mode 100644 openscenario/openscenario_validator/configure/OpenSCENARIO-1.2.xsd create mode 100644 openscenario/openscenario_validator/configure/schema.cpp create mode 100644 openscenario/openscenario_validator/include/openscenario_validator/schema.hpp rename openscenario/{openscenario_utility/include/openscenario_utility/xml_validator.hpp => openscenario_validator/include/openscenario_validator/validator.hpp} (51%) create mode 100644 openscenario/openscenario_validator/package.xml create mode 100644 openscenario/openscenario_validator/src/validator.cpp diff --git a/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp index 5f837af993b..b78d51db8cf 100644 --- a/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp @@ -90,17 +90,11 @@ UserDefinedValueCondition::UserDefinedValueCondition(const pugi::xml_node & node std::make_pair( "currentMinimumRiskManeuverState.state", [result]() { - auto s = asAutoware(result.str(1)).getMinimumRiskManeuverStateName(); - std::cout << "currentMinimumRiskManeuverState.state is called : " << s << std::endl; - return make(s); + return make(asAutoware(result.str(1)).getMinimumRiskManeuverStateName()); }), std::make_pair( "currentEmergencyState", - [result]() { - auto s = asAutoware(result.str(1)).getEmergencyStateName(); - std::cout << "currentEmergencyState is called : " << s << std::endl; - return make(s); - }), + [result]() { return make(asAutoware(result.str(1)).getEmergencyStateName()); }), std::make_pair( "currentTurnIndicatorsState", [result]() { diff --git a/openscenario/openscenario_preprocessor/CMakeLists.txt b/openscenario/openscenario_preprocessor/CMakeLists.txt index f1ffba21828..9c6d69fbcaf 100644 --- a/openscenario/openscenario_preprocessor/CMakeLists.txt +++ b/openscenario/openscenario_preprocessor/CMakeLists.txt @@ -11,20 +11,15 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") endif() find_package(ament_cmake_auto REQUIRED) -find_package(PkgConfig REQUIRED) -pkg_check_modules(XercesC xerces-c) -ament_auto_find_build_dependencies() +find_package(XercesC REQUIRED) -# global includes -include_directories(${XercesC_INCLUDE_DIRS}) +ament_auto_find_build_dependencies() -# common shared library -ament_auto_add_library(${PROJECT_NAME} SHARED src/${PROJECT_NAME}.cpp) -target_link_libraries(${PROJECT_NAME} ${XercesC_LIBRARIES}) +ament_auto_add_executable(${PROJECT_NAME}_node + src/${PROJECT_NAME}.cpp + src/${PROJECT_NAME}_node.cpp) -# node -ament_auto_add_executable(${PROJECT_NAME}_node src/${PROJECT_NAME}_node.cpp) -target_link_libraries(${PROJECT_NAME}_node ${PROJECT_NAME}) +target_link_libraries(${PROJECT_NAME}_node XercesC::XercesC) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) diff --git a/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp b/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp index 6263c158110..ba04f6d72bf 100644 --- a/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp +++ b/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp @@ -15,49 +15,48 @@ #ifndef OPENSCENARIO_PREPROCESSOR__OPENSCENARIO_PREPROCESSOR_HPP_ #define OPENSCENARIO_PREPROCESSOR__OPENSCENARIO_PREPROCESSOR_HPP_ -#include #include #include -#include +#include +#include namespace openscenario_preprocessor { -struct ScenarioSet +struct Scenario { - ScenarioSet() = default; + Scenario() = default; - explicit ScenarioSet(std::string path, int expect, float frame_rate) + explicit Scenario(const boost::filesystem::path & path, int expect, double frame_rate) : path(path), expect(expect), frame_rate(frame_rate) { } - std::string path; + boost::filesystem::path path; int expect; - float frame_rate; + double frame_rate; }; class Preprocessor { public: - explicit Preprocessor(boost::filesystem::path xsd_path, boost::filesystem::path output_directory) - : xml_validator(xsd_path), output_directory(output_directory) + explicit Preprocessor(const boost::filesystem::path & output_directory) + : validate(), output_directory(output_directory) { + if (not boost::filesystem::exists(output_directory)) { + boost::filesystem::create_directories(output_directory); + } } protected: - void preprocessScenario(ScenarioSet &); + void preprocessScenario(const Scenario &); - [[nodiscard]] bool validateXOSC( - const boost::filesystem::path & target_file, const boost::filesystem::path & xsd_file, - bool verbose = false); - - std::deque preprocessed_scenarios; + std::queue preprocessed_scenarios; std::mutex preprocessed_scenarios_mutex; - openscenario_utility::XMLValidator xml_validator; + openscenario_validator::OpenSCENARIOValidator validate; boost::filesystem::path output_directory; }; diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 6c5983fee5c..590b628ee5b 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -11,8 +11,9 @@ openscenario_interpreter openscenario_preprocessor_msgs - openscenario_utility + openscenario_validator rclcpp + xerces ament_cmake_clang_format ament_cmake_copyright diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp index 48652e67128..967a084b8fd 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp @@ -13,80 +13,78 @@ // limitations under the License. #include +#include #include #include -#include +#include #include namespace openscenario_preprocessor { -void Preprocessor::preprocessScenario(ScenarioSet & scenario) +void Preprocessor::preprocessScenario(const Scenario & scenario) { using openscenario_interpreter::OpenScenario; using openscenario_interpreter::ParameterValueDistribution; + using openscenario_interpreter::ParameterValueDistributionDefinition; - if (xml_validator.validate(scenario.path)) { - if (auto script = std::make_shared(scenario.path); - script->category.is_also()) { - auto & parameter_value_distribution = script->category.as(); - auto base_scenario_path = parameter_value_distribution.scenario_file.filepath; + if (validate(scenario.path)) { + if (OpenScenario script{scenario.path}; + script.category.is()) { + auto & parameter_value_distribution = script.category.as(); + auto scenario_file_path = parameter_value_distribution.scenario_file.filepath; - if (boost::filesystem::exists(base_scenario_path)) { - if (xml_validator.validate(base_scenario_path)) { - auto base_scenario = std::make_shared(base_scenario_path); - auto p = parameter_value_distribution.derive(); + if (boost::filesystem::exists(scenario_file_path) and validate(scenario_file_path)) { + OpenScenario scenario_file{scenario_file_path}; - for (const auto & parameter_list : p | boost::adaptors::indexed()) { - pugi::xml_document derived_script; - derived_script.reset(base_scenario->script); // deep copy + auto p = parameter_value_distribution.derive(); - auto parameter_declarations = - derived_script.document_element() - .select_node(pugi::xpath_query{"/OpenSCENARIO/ParameterDeclarations"}) - .node(); + for (const auto & parameter_list : p | boost::adaptors::indexed()) { + pugi::xml_document derived_script; - // embedding parameter values - for (const auto & [name, value] : *parameter_list.value()) { - if (auto parameter_node = - parameter_declarations.find_child_by_attribute("name", name.c_str()); - parameter_node) { - std::stringstream parameter_stringstream; - parameter_stringstream << value; - parameter_node.attribute("value").set_value(parameter_stringstream.str().c_str()); - } else { - std::cout << "Parameter " << name << " not found in base scenario" << std::endl; - } - } + derived_script.reset(scenario_file.script); // deep copy - ScenarioSet derived_scenario = scenario; + auto parameter_declarations = + derived_script.document_element() + .select_node(pugi::xpath_query{"/OpenSCENARIO/ParameterDeclarations"}) + .node(); - // generate new scenario file name - boost::filesystem::path derived_scenario_path(derived_scenario.path); - derived_scenario_path = output_directory / derived_scenario_path.filename(); - derived_scenario_path.replace_extension( - std::to_string(parameter_list.index()) + derived_scenario_path.extension().string()); + // embedding parameter values + for (const auto & [name, value] : *parameter_list.value()) { + if ( + auto parameter_node = + parameter_declarations.find_child_by_attribute("name", name.c_str())) { + parameter_node.attribute("value").set_value( + boost::lexical_cast(value).c_str()); + } else { + std::cerr << "Parameter " << std::quoted(name) << " is not declared in scenario " + << std::quoted(scenario_file_path.string()) << ", so ignore it." + << std::endl; + } + } - derived_scenario.path = derived_scenario_path.string(); + const auto derived_scenario_path = + output_directory / + (scenario.path.stem().string() + "." + std::to_string(parameter_list.index()) + + scenario.path.extension().string()); - if (not boost::filesystem::exists(output_directory)) { - boost::filesystem::create_directories(output_directory); - } - derived_script.save_file(derived_scenario.path.c_str()); + derived_script.save_file(derived_scenario_path.c_str()); - preprocessed_scenarios.emplace_back(derived_scenario); - } - } else { - throw common::Error("base scenario is not valid : " + base_scenario_path.string()); + preprocessed_scenarios.emplace( + derived_scenario_path, scenario.expect, scenario.frame_rate); } } else { - throw common::Error("base scenario does not exist : " + base_scenario_path.string()); + throw common::Error( + "Scenario file ", std::quoted(scenario_file_path.string()), + " described in ParameterDistributionDefinition file ", + std::quoted(scenario.path.string()), + " does not exist. Please check if the file path is correct."); } } else { // normal scenario - preprocessed_scenarios.emplace_back(scenario); + preprocessed_scenarios.push(scenario); } } else { - throw common::Error("the scenario file is not valid. Please check your scenario"); + throw common::Error("The scenario file is not valid. Please check your scenario"); } } } // namespace openscenario_preprocessor diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp index 83536431d7b..124561d2ffe 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include #include #include #include @@ -24,14 +23,12 @@ class PreprocessorNode : public rclcpp::Node, public openscenario_preprocessor::Preprocessor { public: - explicit PreprocessorNode(const rclcpp::NodeOptions & options, const std::string xsd_path) + explicit PreprocessorNode(const rclcpp::NodeOptions & options) : rclcpp::Node("preprocessor", options), - openscenario_preprocessor::Preprocessor( - xsd_path, - [this] { - declare_parameter("output_directory", "/tmp/openscenario_preprocessor"); - return get_parameter("output_directory").as_string(); - }()), + openscenario_preprocessor::Preprocessor([this] { + declare_parameter("output_directory", "/tmp/openscenario_preprocessor"); + return get_parameter("output_directory").as_string(); + }()), load_server(create_service( "~/load", [this]( @@ -39,15 +36,14 @@ class PreprocessorNode : public rclcpp::Node, public openscenario_preprocessor:: openscenario_preprocessor_msgs::srv::Load::Response::SharedPtr response) -> void { auto lock = std::lock_guard(preprocessed_scenarios_mutex); try { - auto s = openscenario_preprocessor::ScenarioSet( - request->path, request->expect, request->frame_rate); - preprocessScenario(s); + preprocessScenario(openscenario_preprocessor::Scenario( + request->path, request->expect, request->frame_rate)); response->has_succeeded = true; response->message = "success"; } catch (std::exception & e) { response->has_succeeded = false; response->message = e.what(); - preprocessed_scenarios.clear(); + std::queue().swap(preprocessed_scenarios); } })), derive_server(create_service( @@ -59,10 +55,10 @@ class PreprocessorNode : public rclcpp::Node, public openscenario_preprocessor:: if (preprocessed_scenarios.empty()) { response->path = "no output"; } else { - response->path = preprocessed_scenarios.front().path; + response->path = preprocessed_scenarios.front().path.string(); response->expect = preprocessed_scenarios.front().expect; response->frame_rate = preprocessed_scenarios.front().frame_rate; - preprocessed_scenarios.pop_front(); + preprocessed_scenarios.pop(); } })), check_server(create_service( @@ -94,10 +90,7 @@ int main(const int argc, char const * const * const argv) rclcpp::NodeOptions options{}; - std::string xsd_path = ament_index_cpp::get_package_share_directory("openscenario_utility") + - "/../lib/openscenario_utility/resources/OpenSCENARIO-1.2.xsd"; - - auto node = std::make_shared(options, xsd_path); + auto node = std::make_shared(options); executor.add_node((*node).get_node_base_interface()); diff --git a/openscenario/openscenario_utility/CMakeLists.txt b/openscenario/openscenario_utility/CMakeLists.txt index 2829634aaf6..54674273c1a 100644 --- a/openscenario/openscenario_utility/CMakeLists.txt +++ b/openscenario/openscenario_utility/CMakeLists.txt @@ -11,11 +11,4 @@ install( DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/${PROJECT_NAME}/ DESTINATION lib/${PROJECT_NAME}) -install( - DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/include/ - DESTINATION include -) - -ament_export_include_directories(include) - ament_package() diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index c6bf99626ce..4417b2e8423 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -14,7 +14,6 @@ python3-yaml rclcpp rclpy - xerces ament_cmake diff --git a/openscenario/openscenario_validator/.gitignore b/openscenario/openscenario_validator/.gitignore new file mode 100644 index 00000000000..6ff348f1ae8 --- /dev/null +++ b/openscenario/openscenario_validator/.gitignore @@ -0,0 +1 @@ +src/schema.cpp diff --git a/openscenario/openscenario_validator/CMakeLists.txt b/openscenario/openscenario_validator/CMakeLists.txt new file mode 100644 index 00000000000..14a206747a9 --- /dev/null +++ b/openscenario/openscenario_validator/CMakeLists.txt @@ -0,0 +1,21 @@ +cmake_minimum_required(VERSION 3.16.3) # Ubuntu 20.04 default CMake version + +project(openscenario_validator VERSION 0.0.0) + +find_package(ament_cmake_auto REQUIRED) +find_package(XercesC REQUIRED) + +file(READ ${CMAKE_CURRENT_SOURCE_DIR}/configure/OpenSCENARIO-1.2.xsd ${PROJECT_NAME}_OPENSCENARIO_1_2_XSD) + +configure_file(${CMAKE_CURRENT_SOURCE_DIR}/configure/schema.cpp ${CMAKE_CURRENT_SOURCE_DIR}/src/schema.cpp) + +ament_auto_add_library(${PROJECT_NAME} STATIC + ${CMAKE_CURRENT_SOURCE_DIR}/src/schema.cpp + ${CMAKE_CURRENT_SOURCE_DIR}/src/validator.cpp) + +set_target_properties(${PROJECT_NAME} PROPERTIES + CXX_EXTENSIONS OFF + CXX_STANDARD 17 + CXX_STANDARD_REQUIRED ON) + +ament_auto_package() diff --git a/openscenario/openscenario_validator/configure/OpenSCENARIO-1.2.xsd b/openscenario/openscenario_validator/configure/OpenSCENARIO-1.2.xsd new file mode 100644 index 00000000000..67ea8b5b340 --- /dev/null +++ b/openscenario/openscenario_validator/configure/OpenSCENARIO-1.2.xsd @@ -0,0 +1,2419 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + deprecated + + + + + + + + + + + + + + + + + + + deprecated + + + deprecated + + + deprecated + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + deprecated + + + + + + + + + + + + + + + deprecated + + + deprecated + + + deprecated + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + deprecated + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + diff --git a/openscenario/openscenario_validator/configure/schema.cpp b/openscenario/openscenario_validator/configure/schema.cpp new file mode 100644 index 00000000000..4330aa265a1 --- /dev/null +++ b/openscenario/openscenario_validator/configure/schema.cpp @@ -0,0 +1,20 @@ +// 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_validator +{ +const std::string_view schema = R"###(${${PROJECT_NAME}_OPENSCENARIO_1_2_XSD})###"; +} // namespace openscenario_validator diff --git a/openscenario/openscenario_validator/include/openscenario_validator/schema.hpp b/openscenario/openscenario_validator/include/openscenario_validator/schema.hpp new file mode 100644 index 00000000000..5a06a279c5e --- /dev/null +++ b/openscenario/openscenario_validator/include/openscenario_validator/schema.hpp @@ -0,0 +1,20 @@ +// 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_validator +{ +extern const std::string_view schema; +} // namespace openscenario_validator diff --git a/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp b/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp similarity index 51% rename from openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp rename to openscenario/openscenario_validator/include/openscenario_validator/validator.hpp index bce38920596..437412408cf 100644 --- a/openscenario/openscenario_utility/include/openscenario_utility/xml_validator.hpp +++ b/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp @@ -12,44 +12,59 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OPENSCENARIO_UTILITY__XML_VALIDATOR_HPP_ -#define OPENSCENARIO_UTILITY__XML_VALIDATOR_HPP_ +#ifndef OPENSCENARIO_VALIDATOR__VALIDATOR_HPP_ +#define OPENSCENARIO_VALIDATOR__VALIDATOR_HPP_ #include -#include +#include +#include +#include +#include #include -#include #include -#include #include -namespace openscenario_utility +namespace openscenario_validator { -class XMLValidator +struct XMLPlatform { -public: - explicit XMLValidator(boost::filesystem::path xsd_file) : xsd_file(xsd_file) - { - xercesc::XMLPlatformUtils::Initialize(); - } + XMLPlatform(); - ~XMLValidator() { xercesc::XMLPlatformUtils::Terminate(); } + ~XMLPlatform(); +}; - [[nodiscard]] bool validate(const boost::filesystem::path & xml_file) noexcept - { - try { - auto parser = xercesc::XercesDOMParser(); - parser.loadGrammar(xsd_file.string().c_str(), xercesc::Grammar::SchemaGrammarType, true); +static XMLPlatform platform{}; + +class OpenSCENARIOValidator +{ + xercesc::XercesDOMParser parser; + + xercesc::MemBufInputSource input_source; + + std::unique_ptr error_handler; - auto error_handler = std::make_unique(); +public: + explicit OpenSCENARIOValidator() + : input_source(reinterpret_cast(schema.data()), schema.size(), "xsd"), + error_handler(std::make_unique()) + { + if (not parser.loadGrammar(input_source, xercesc::Grammar::SchemaGrammarType)) { + throw std::runtime_error( + "Failed to load XSD schema. This is an unexpected error and an implementation issue. " + "Please contact the developer."); + } else { parser.setErrorHandler(error_handler.get()); parser.setValidationScheme(xercesc::XercesDOMParser::Val_Auto); parser.setDoNamespaces(true); parser.setDoSchema(true); parser.setValidationConstraintFatal(true); + } + } + [[nodiscard]] auto validate(const boost::filesystem::path & xml_file) noexcept -> bool + { + try { parser.parse(xml_file.string().c_str()); - return parser.getErrorCount() == 0; } catch (const xercesc::XMLException & ex) { std::cerr << "Error: " << ex.getMessage() << std::endl; @@ -60,7 +75,12 @@ class XMLValidator } } - boost::filesystem::path xsd_file; + template + [[nodiscard]] auto operator()(Ts &&... xs) noexcept -> decltype(auto) + { + return validate(std::forward(xs)...); + } }; -} // namespace openscenario_utility -#endif //OPENSCENARIO_UTILITY__XML_VALIDATOR_HPP_ +} // namespace openscenario_validator + +#endif //OPENSCENARIO_VALIDATOR__VALIDATOR_HPP_ diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml new file mode 100644 index 00000000000..be2bfdb3da6 --- /dev/null +++ b/openscenario/openscenario_validator/package.xml @@ -0,0 +1,15 @@ + + + + openscenario_validator + 0.6.7 + Validator for OpenSCENARIO 1.2 + Kotaro Yoshimoto + Apache License 2.0 + ament_cmake_auto + xerces + + ament_cmake + + + diff --git a/openscenario/openscenario_validator/src/validator.cpp b/openscenario/openscenario_validator/src/validator.cpp new file mode 100644 index 00000000000..fd8cf54b334 --- /dev/null +++ b/openscenario/openscenario_validator/src/validator.cpp @@ -0,0 +1,35 @@ +// 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 openscenario_validator +{ +static std::size_t count = 0; + +XMLPlatform::XMLPlatform() +{ + if (not count++) { + xercesc::XMLPlatformUtils::Initialize(); + } +} + +XMLPlatform::~XMLPlatform() +{ + if (not --count) { + xercesc::XMLPlatformUtils::Terminate(); + } +} +} // namespace openscenario_validator From ba236d07aaae4e199cb1616d3049e26ec4c6f7b1 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 26 Apr 2023 13:52:36 +0900 Subject: [PATCH 079/120] apply yamasaki-san's second patch --- .../src/openscenario_preprocessor.cpp | 85 +++++++++---------- .../openscenario_validator/validator.hpp | 72 +++++++++++----- 2 files changed, 92 insertions(+), 65 deletions(-) diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp index 967a084b8fd..2e21b872c90 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp @@ -27,64 +27,61 @@ void Preprocessor::preprocessScenario(const Scenario & scenario) using openscenario_interpreter::ParameterValueDistribution; using openscenario_interpreter::ParameterValueDistributionDefinition; - if (validate(scenario.path)) { - if (OpenScenario script{scenario.path}; - script.category.is()) { - auto & parameter_value_distribution = script.category.as(); - auto scenario_file_path = parameter_value_distribution.scenario_file.filepath; + validate(scenario.path); - if (boost::filesystem::exists(scenario_file_path) and validate(scenario_file_path)) { - OpenScenario scenario_file{scenario_file_path}; + if (OpenScenario script{scenario.path}; + script.category.is()) { + auto & parameter_value_distribution = script.category.as(); + auto scenario_file_path = parameter_value_distribution.scenario_file.filepath; - auto p = parameter_value_distribution.derive(); + if (boost::filesystem::exists(scenario_file_path)) { + validate(scenario_file_path); - for (const auto & parameter_list : p | boost::adaptors::indexed()) { - pugi::xml_document derived_script; + OpenScenario scenario_file{scenario_file_path}; - derived_script.reset(scenario_file.script); // deep copy + auto p = parameter_value_distribution.derive(); - auto parameter_declarations = - derived_script.document_element() - .select_node(pugi::xpath_query{"/OpenSCENARIO/ParameterDeclarations"}) - .node(); + for (const auto & parameter_list : p | boost::adaptors::indexed()) { + pugi::xml_document derived_script; - // embedding parameter values - for (const auto & [name, value] : *parameter_list.value()) { - if ( - auto parameter_node = - parameter_declarations.find_child_by_attribute("name", name.c_str())) { - parameter_node.attribute("value").set_value( - boost::lexical_cast(value).c_str()); - } else { - std::cerr << "Parameter " << std::quoted(name) << " is not declared in scenario " - << std::quoted(scenario_file_path.string()) << ", so ignore it." - << std::endl; - } + derived_script.reset(scenario_file.script); // deep copy + + auto parameter_declarations = + derived_script.document_element() + .select_node(pugi::xpath_query{"/OpenSCENARIO/ParameterDeclarations"}) + .node(); + + // embedding parameter values + for (const auto & [name, value] : *parameter_list.value()) { + if ( + auto parameter_node = + parameter_declarations.find_child_by_attribute("name", name.c_str())) { + parameter_node.attribute("value").set_value( + boost::lexical_cast(value).c_str()); + } else { + std::cerr << "Parameter " << std::quoted(name) << " is not declared in scenario " + << std::quoted(scenario_file_path.string()) << ", so ignore it." << std::endl; } + } - const auto derived_scenario_path = - output_directory / - (scenario.path.stem().string() + "." + std::to_string(parameter_list.index()) + - scenario.path.extension().string()); + const auto derived_scenario_path = + output_directory / + (scenario.path.stem().string() + "." + std::to_string(parameter_list.index()) + + scenario.path.extension().string()); - derived_script.save_file(derived_scenario_path.c_str()); + derived_script.save_file(derived_scenario_path.c_str()); - preprocessed_scenarios.emplace( - derived_scenario_path, scenario.expect, scenario.frame_rate); - } - } else { - throw common::Error( - "Scenario file ", std::quoted(scenario_file_path.string()), - " described in ParameterDistributionDefinition file ", - std::quoted(scenario.path.string()), - " does not exist. Please check if the file path is correct."); + preprocessed_scenarios.emplace(derived_scenario_path, scenario.expect, scenario.frame_rate); } } else { - // normal scenario - preprocessed_scenarios.push(scenario); + std::stringstream what; + what << "Scenario file " << std::quoted(scenario_file_path.string()) + << " described in ParameterDistributionDefinition file " + << std::quoted(scenario.path.string()) << " does not exist"; + throw std::runtime_error(what.str()); } } else { - throw common::Error("The scenario file is not valid. Please check your scenario"); + preprocessed_scenarios.push(scenario); // normal scenario } } } // namespace openscenario_preprocessor diff --git a/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp b/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp index 437412408cf..ac1cacfbd6d 100644 --- a/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp +++ b/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp @@ -18,10 +18,12 @@ #include #include #include +#include #include -#include +#include #include #include +#include #include namespace openscenario_validator @@ -37,46 +39,74 @@ static XMLPlatform platform{}; class OpenSCENARIOValidator { + struct ErrorHandler : public xercesc::HandlerBase + { + using xercesc::HandlerBase::HandlerBase; + + template + auto makeErrorMessage(const String & category, const xercesc::SAXParseException & e) + { + // The following exception message is formatted to resemble GCC's + // compilation error message. + std::stringstream what; + what << xercesc::XMLString::transcode(e.getSystemId()) << ":" << e.getLineNumber() << ":" + << e.getColumnNumber() << ": " << category << ": " + << xercesc::XMLString::transcode(e.getMessage()); + return what.str(); + } + + auto warning(const xercesc::SAXParseException & e) -> void override + { + std::cerr << makeErrorMessage("warning", e) << std::endl; + } + + auto error(const xercesc::SAXParseException & e) -> void override + { + throw std::runtime_error(makeErrorMessage("error", e)); + } + + auto fatalError(const xercesc::SAXParseException & e) -> void override + { + throw std::runtime_error(makeErrorMessage("fatal", e)); + } + }; + xercesc::XercesDOMParser parser; - xercesc::MemBufInputSource input_source; + ErrorHandler error_handler; - std::unique_ptr error_handler; + static constexpr auto schema_filepath = "/tmp/OpenSCENARIO-1.2.xsd"; public: explicit OpenSCENARIOValidator() - : input_source(reinterpret_cast(schema.data()), schema.size(), "xsd"), - error_handler(std::make_unique()) { - if (not parser.loadGrammar(input_source, xercesc::Grammar::SchemaGrammarType)) { + if (auto file = std::ofstream(schema_filepath, std::ios::trunc)) { + file << schema; + } else { + throw std::system_error(errno, std::system_category()); + } + + if (not parser.loadGrammar(schema_filepath, xercesc::Grammar::SchemaGrammarType)) { throw std::runtime_error( "Failed to load XSD schema. This is an unexpected error and an implementation issue. " "Please contact the developer."); } else { - parser.setErrorHandler(error_handler.get()); - parser.setValidationScheme(xercesc::XercesDOMParser::Val_Auto); parser.setDoNamespaces(true); parser.setDoSchema(true); - parser.setValidationConstraintFatal(true); + parser.setErrorHandler(&error_handler); + parser.setExternalNoNamespaceSchemaLocation(schema_filepath); + parser.setValidationSchemaFullChecking(true); + parser.setValidationScheme(xercesc::XercesDOMParser::Val_Always); } } - [[nodiscard]] auto validate(const boost::filesystem::path & xml_file) noexcept -> bool + auto validate(const boost::filesystem::path & xml_file) -> void { - try { - parser.parse(xml_file.string().c_str()); - return parser.getErrorCount() == 0; - } catch (const xercesc::XMLException & ex) { - std::cerr << "Error: " << ex.getMessage() << std::endl; - return false; - } catch (...) { - std::cerr << "Error: Unknown exception" << std::endl; - return false; - } + parser.parse(xml_file.string().c_str()); } template - [[nodiscard]] auto operator()(Ts &&... xs) noexcept -> decltype(auto) + auto operator()(Ts &&... xs) -> decltype(auto) { return validate(std::forward(xs)...); } From 4cf5657920dcc1392db382d0c0f0ae6252a8e71c Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 26 Apr 2023 13:53:15 +0900 Subject: [PATCH 080/120] chore: fix cspell error --- .github/workflows/custom_spell.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/custom_spell.json b/.github/workflows/custom_spell.json index 8c47782c42b..c85420bd0f1 100644 --- a/.github/workflows/custom_spell.json +++ b/.github/workflows/custom_spell.json @@ -3,7 +3,7 @@ "*.drawio", "*/**/CHANGELOG.rst", "external/lanelet2_matching/**", - "openscenario/openscenario_utility/openscenario_utility/resources/*.xsd" + "*.xsd" ], "words": [ "ARGN", From e0741edbf3b966f8a758c6be2b83a7064dc18db1 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 26 Apr 2023 13:53:31 +0900 Subject: [PATCH 081/120] apply linter --- openscenario/openscenario_validator/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index be2bfdb3da6..5e4a4ccf1ac 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -12,4 +12,3 @@ ament_cmake - From 51d09ae0c0c9ce03896573b78e04664b6d5bf118 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 2 May 2023 15:39:07 +0900 Subject: [PATCH 082/120] refactor(openscenario_interpreter): delete unused functions --- .../parameter_distribution.hpp | 8 +++--- .../syntax/deterministic.hpp | 6 ----- ...rministic_multi_parameter_distribution.hpp | 6 ----- ...ministic_single_parameter_distribution.hpp | 6 ----- .../syntax/distribution_range.hpp | 6 ----- .../syntax/distribution_set.hpp | 6 ----- .../syntax/histogram.hpp | 4 --- .../syntax/normal_distribution.hpp | 4 --- .../syntax/parameter_value_distribution.hpp | 6 ----- .../syntax/poisson_distribution.hpp | 4 --- .../syntax/probability_distribution_set.hpp | 4 --- .../syntax/stochastic.hpp | 6 ----- .../syntax/stochastic_distribution.hpp | 4 --- .../syntax/uniform_distribution.hpp | 5 +--- .../syntax/value_set_distribution.hpp | 6 ----- .../src/syntax/deterministic.cpp | 27 ------------------- ...rministic_multi_parameter_distribution.cpp | 13 --------- ...ministic_single_parameter_distribution.cpp | 22 --------------- .../src/syntax/distribution_range.cpp | 12 --------- .../src/syntax/distribution_set.cpp | 12 --------- .../src/syntax/histogram.cpp | 7 ----- .../src/syntax/normal_distribution.cpp | 7 ----- .../syntax/parameter_value_distribution.cpp | 18 ------------- .../src/syntax/poisson_distribution.cpp | 7 ----- .../syntax/probability_distribution_set.cpp | 8 ------ .../src/syntax/stochastic.cpp | 16 ----------- .../src/syntax/stochastic_distribution.cpp | 15 ----------- .../src/syntax/uniform_distribution.cpp | 7 ----- .../src/syntax/value_set_distribution.cpp | 12 --------- 29 files changed, 5 insertions(+), 259 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp index 475a9018e5f..3f501404873 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -43,23 +43,23 @@ struct ParallelDerivableParameterDistributionBase }; // generator types distribution -struct SingleParameterDistributionBase : public ParallelDerivableParameterDistributionBase +struct SingleParameterDistributionBase { virtual auto derive() -> SingleUnnamedParameterDistribution = 0; }; -struct MultiParameterDistributionBase : public ParallelDerivableParameterDistributionBase +struct MultiParameterDistributionBase { virtual auto derive() -> ParameterDistribution = 0; }; -struct StochasticParameterDistributionBase : public ParallelDerivableParameterDistributionBase +struct StochasticParameterDistributionBase { virtual auto derive() -> Object = 0; }; // container types of distribution data generator -struct ParameterDistributionContainer : public ParallelDerivableParameterDistributionBase +struct ParameterDistributionContainer { virtual auto derive() -> ParameterDistribution = 0; }; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp index bcd395a407c..2d18656ef95 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp @@ -40,12 +40,6 @@ struct Deterministic : public ParameterDistributionContainer explicit Deterministic(const pugi::xml_node &, Scope & scope); auto derive() -> ParameterDistribution override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; - - auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp index eb43dc1215e..b9e241008d5 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp @@ -38,12 +38,6 @@ struct DeterministicMultiParameterDistribution : public DeterministicMultiParame explicit DeterministicMultiParameterDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> ParameterDistribution override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; - - auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index 4d06f2efb83..cc783a9d325 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -42,12 +42,6 @@ struct DeterministicSingleParameterDistribution explicit DeterministicSingleParameterDistribution(const pugi::xml_node &, Scope &); auto derive() -> ParameterDistribution override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; - - auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index dfcbfd7fe56..d8ae87e1a20 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -43,12 +43,6 @@ struct DistributionRange : private Scope, public ComplexType, public SingleParam explicit DistributionRange(const pugi::xml_node &, Scope &); auto derive() -> SingleUnnamedParameterDistribution override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; - - auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index 4bdc92c2ae4..32db787204f 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -39,12 +39,6 @@ struct DistributionSet : private Scope, public ComplexType, public SingleParamet explicit DistributionSet(const pugi::xml_node &, Scope & scope); auto derive() -> SingleUnnamedParameterDistribution override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; - - auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index 84db5fd71f5..61480d69d31 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -61,10 +61,6 @@ struct Histogram : public ComplexType, private Scope, public StochasticParameter explicit Histogram(const pugi::xml_node &, Scope & scope); auto derive() -> Object override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp index 352b2f7a928..df914527978 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp @@ -53,10 +53,6 @@ struct NormalDistribution : public ComplexType, explicit NormalDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> Object override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp index adfa9b7d505..02127cd7e52 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp @@ -40,12 +40,6 @@ struct ParameterValueDistribution : public DistributionDefinition, explicit ParameterValueDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> ParameterDistribution override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; - - auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index 02cc5950bed..744b668fde0 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -48,10 +48,6 @@ struct PoissonDistribution : public ComplexType, explicit PoissonDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> Object override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index 2c9de30ff34..9143f16d8bb 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -58,10 +58,6 @@ struct ProbabilityDistributionSet : public ComplexType, explicit ProbabilityDistributionSet(const pugi::xml_node &, Scope & scope); auto derive() -> Object override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp index 5ca321ab594..55e63230b23 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp @@ -50,12 +50,6 @@ struct Stochastic : public ComplexType, public ParameterDistributionContainer, p explicit Stochastic(const pugi::xml_node &, Scope & scope); auto derive() -> ParameterDistribution override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; - - auto getNumberOfDeriveScenarios() const -> std::size_t override { return number_of_test_runs; } }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp index 7842c6289e3..a35332d7ae5 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp @@ -42,10 +42,6 @@ struct StochasticDistribution : public StochasticDistributionType, explicit StochasticDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> Object override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index de818528020..87bdebdfc59 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -19,6 +19,7 @@ #include #include #include +#include namespace openscenario_interpreter { @@ -44,10 +45,6 @@ struct UniformDistribution : public ComplexType, explicit UniformDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> Object override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp index 02b6f8242d1..dfd9e605e68 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp @@ -39,12 +39,6 @@ struct ValueSetDistribution : public Scope, public MultiParameterDistributionBas explicit ValueSetDistribution(const pugi::xml_node &, Scope & scope); auto derive() -> ParameterDistribution override; - - auto derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList override; - - auto getNumberOfDeriveScenarios() const -> std::size_t override; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp index 376774e8bfe..8c3d20174b4 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic.cpp @@ -36,32 +36,5 @@ auto Deterministic::derive() -> ParameterDistribution } return distribution; } - -auto Deterministic::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList -{ - auto child = - std::next(deterministic_parameter_distributions.begin(), std::floor(local_index / local_size)); - return apply( - [&](auto & child_distribution) { - return child_distribution.derive( - local_index % local_size, local_size / deterministic_parameter_distributions.size(), - global_index, global_size); - }, - (DeterministicParameterDistribution &)*child); -} - -auto Deterministic::getNumberOfDeriveScenarios() const -> std::size_t -{ - return std::accumulate( - deterministic_parameter_distributions.begin(), deterministic_parameter_distributions.end(), 1, - [](std::size_t pre_result, auto distribution) { - return pre_result * - apply( - [](auto & distribution) { return distribution.getNumberOfDeriveScenarios(); }, - distribution); - }); -} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp index a8bef18d055..7e4563239fb 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_multi_parameter_distribution.cpp @@ -29,18 +29,5 @@ auto DeterministicMultiParameterDistribution::derive() -> ParameterDistribution { return DeterministicMultiParameterDistributionType::derive(); } - -auto DeterministicMultiParameterDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList -{ - return DeterministicMultiParameterDistributionType::derive( - local_index, local_size, global_index, global_size); -} - -auto DeterministicMultiParameterDistribution::getNumberOfDeriveScenarios() const -> std::size_t -{ - return DeterministicMultiParameterDistributionType::getNumberOfDeriveScenarios(); -} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp index ac420ce89cc..4c79c3d7a76 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp @@ -40,27 +40,5 @@ auto DeterministicSingleParameterDistribution::derive() -> ParameterDistribution }, *this); } - -auto DeterministicSingleParameterDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList -{ - return { - {parameter_name, apply( - [&](auto && single_parameter_distribution) { - return single_parameter_distribution.derive( - local_index, local_size, global_index, global_size); - }, - (DeterministicSingleParameterDistributionType &)*this) - .begin() - ->second}}; -} - -auto DeterministicSingleParameterDistribution::getNumberOfDeriveScenarios() const -> std::size_t -{ - return apply( - [](auto & unnamed_distribution) { return unnamed_distribution.getNumberOfDeriveScenarios(); }, - (DeterministicSingleParameterDistributionType &)*this); -} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp index a6c9ac0e6c1..e2c1c5bf8f6 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp @@ -35,17 +35,5 @@ auto DistributionRange::derive() -> SingleUnnamedParameterDistribution } return unnamed_distribution; } - -auto DistributionRange::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList -{ - return ParameterList({{"", make(range.lower_limit + step_width * local_index)}}); -} - -auto DistributionRange::getNumberOfDeriveScenarios() const -> std::size_t -{ - return int((range.upper_limit - range.lower_limit) / step_width) + 1; -} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp index 9c11257ae62..7a023200e43 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_set.cpp @@ -32,17 +32,5 @@ auto DistributionSet::derive() -> SingleUnnamedParameterDistribution } return distribution; } - -auto DistributionSet::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList -{ - return ParameterList({{"", make(std::next(elements.begin(), local_index)->value)}}); -} - -auto DistributionSet::getNumberOfDeriveScenarios() const -> std::size_t -{ - return std::size(elements); -} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp index 593bf2bb6d7..95e4281b609 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp @@ -29,12 +29,5 @@ Histogram::Histogram(const pugi::xml_node & node, openscenario_interpreter::Scop } auto Histogram::derive() -> Object { return make(distribute(random_engine)); } - -auto Histogram::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList -{ - return ParameterList({{"", make(distribute(random_engine))}}); -} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp index d17ddb88189..690402daa28 100644 --- a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp @@ -30,12 +30,5 @@ NormalDistribution::NormalDistribution( } auto NormalDistribution::derive() -> Object { return make(distribute(random_engine)); } - -auto NormalDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList -{ - return ParameterList({{"", make(distribute(random_engine))}}); -} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp index 4388e37e9c8..8dbb0ae61bc 100644 --- a/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/parameter_value_distribution.cpp @@ -30,23 +30,5 @@ auto ParameterValueDistribution::derive() -> ParameterDistribution return apply( [](auto & distribution) { return distribution.derive(); }, *this); } - -auto ParameterValueDistribution::getNumberOfDeriveScenarios() const -> std::size_t -{ - return apply( - [](auto & distribution) { return distribution.getNumberOfDeriveScenarios(); }, - (DistributionDefinition &)*this); -} - -auto ParameterValueDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList -{ - return apply( - [&](auto & distribution) { - return distribution.derive(local_index, local_size, global_index, global_size); - }, - (DistributionDefinition &)*this); -} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp index d0df2cce5cc..c28dc271046 100644 --- a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp @@ -32,12 +32,5 @@ auto PoissonDistribution::derive() -> Object { return make(range.evaluate(distribute(random_engine))); } - -ParameterList PoissonDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -{ - return ParameterList({{"", make(range.evaluate(distribute(random_engine)))}}); -} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp index 11564c55f54..d635089a7c7 100644 --- a/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/probability_distribution_set.cpp @@ -41,13 +41,5 @@ auto ProbabilityDistributionSet::derive() -> Object std::size_t index = distribute(random_engine); return make(elements.at(index).value); } - -auto ProbabilityDistributionSet::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList -{ - std::size_t index = distribute(random_engine); - return ParameterList{{"", make(elements.at(index).value)}}; -} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp index 0829d2027ba..dce9b512c1e 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp @@ -50,21 +50,5 @@ auto Stochastic::derive() -> ParameterDistribution } return distribution; } - -auto Stochastic::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList -{ - // update random_engine - random_engine.seed(random_seed); - random_engine.discard(global_index); - - // N test_runs : i (0 <= i < N) - // M distributions : j (0 <= j < M) - // index : i * M + j - return std::next(stochastic_distributions.begin(), local_index % stochastic_distributions.size()) - ->derive(local_index, local_size, global_index, global_size); -} - } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp index 3c8b051c433..963ddd6ac8a 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution.cpp @@ -30,20 +30,5 @@ auto StochasticDistribution::derive() -> Object return apply( [](auto & unnamed_distribution) { return unnamed_distribution.derive(); }, *this); } - -auto StochasticDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList -{ - return { - {parameter_name, make(apply( - [&](auto & unnamed_distribution) { - return unnamed_distribution.derive( - local_index, local_size, global_index, global_size); - }, - (StochasticDistributionType &)*this) - .begin() - ->second)}}; -} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index e273ffb28d6..223be5f217e 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -28,12 +28,5 @@ UniformDistribution::UniformDistribution( } auto UniformDistribution::derive() -> Object { return make(distribute(random_engine)); } - -auto UniformDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList -{ - return ParameterList({{"", make(distribute(random_engine))}}); -} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp index 37a432f81c1..eafe1a64f2c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/value_set_distribution.cpp @@ -34,17 +34,5 @@ auto ValueSetDistribution::derive() -> ParameterDistribution } return parameters; } - -auto ValueSetDistribution::derive( - std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList -{ - return *(std::next(parameter_value_sets.begin(), local_index)->evaluate()); -} - -auto ValueSetDistribution::getNumberOfDeriveScenarios() const -> std::size_t -{ - return std::size(parameter_value_sets); -} } // namespace syntax } // namespace openscenario_interpreter From 8020f1d75c07b94a58b97a1f25c215c33a595719 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 12 May 2023 18:38:24 +0900 Subject: [PATCH 083/120] chore: apply linter --- .../src/syntax/user_defined_value_condition.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp index adf67cb5d58..844a8c9dfaf 100644 --- a/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp @@ -91,7 +91,8 @@ UserDefinedValueCondition::UserDefinedValueCondition(const pugi::xml_node & node std::make_pair( "currentMinimumRiskManeuverState.state", [result]() { - return make(asFieldOperatorApplication(result.str(1)).getMinimumRiskManeuverStateName()); + return make( + asFieldOperatorApplication(result.str(1)).getMinimumRiskManeuverStateName()); }), std::make_pair( "currentEmergencyState", From c2036287ee4e11349a52f614fa20816e39a4ac2c Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 7 Aug 2023 14:17:33 +0900 Subject: [PATCH 084/120] fix(openscenario_preprocessor): fix errors due to incomplete following-up to latest master --- .../openscenario_preprocessor/openscenario_preprocessor.hpp | 2 +- .../src/openscenario_preprocessor.cpp | 2 +- .../src/openscenario_preprocessor_node.cpp | 5 ++--- 3 files changed, 4 insertions(+), 5 deletions(-) diff --git a/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp b/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp index 260c7e45639..5f6d1cf226f 100644 --- a/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp +++ b/openscenario/openscenario_preprocessor/include/openscenario_preprocessor/openscenario_preprocessor.hpp @@ -26,7 +26,7 @@ struct Scenario { Scenario() = default; - explicit Scenario(const boost::filesystem::path & path, int expect, double frame_rate) + explicit Scenario(const boost::filesystem::path & path, double frame_rate) : path(path), frame_rate(frame_rate) { } diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp index 2e21b872c90..79c478b6aa9 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor.cpp @@ -71,7 +71,7 @@ void Preprocessor::preprocessScenario(const Scenario & scenario) derived_script.save_file(derived_scenario_path.c_str()); - preprocessed_scenarios.emplace(derived_scenario_path, scenario.expect, scenario.frame_rate); + preprocessed_scenarios.emplace(derived_scenario_path, scenario.frame_rate); } } else { std::stringstream what; diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp index 124561d2ffe..dfeed705912 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp @@ -36,8 +36,8 @@ class PreprocessorNode : public rclcpp::Node, public openscenario_preprocessor:: openscenario_preprocessor_msgs::srv::Load::Response::SharedPtr response) -> void { auto lock = std::lock_guard(preprocessed_scenarios_mutex); try { - preprocessScenario(openscenario_preprocessor::Scenario( - request->path, request->expect, request->frame_rate)); + preprocessScenario( + openscenario_preprocessor::Scenario(request->path, request->frame_rate)); response->has_succeeded = true; response->message = "success"; } catch (std::exception & e) { @@ -56,7 +56,6 @@ class PreprocessorNode : public rclcpp::Node, public openscenario_preprocessor:: response->path = "no output"; } else { response->path = preprocessed_scenarios.front().path.string(); - response->expect = preprocessed_scenarios.front().expect; response->frame_rate = preprocessed_scenarios.front().frame_rate; preprocessed_scenarios.pop(); } From ac4e2e776e77d6bff53cbcf5ca392636f0e3638d Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 21 Nov 2023 23:37:35 +0900 Subject: [PATCH 085/120] chore(cspell): update ignorePaths in custom_spell.json --- .github/workflows/custom_spell.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/custom_spell.json b/.github/workflows/custom_spell.json index edce0beb08f..e361eccb745 100644 --- a/.github/workflows/custom_spell.json +++ b/.github/workflows/custom_spell.json @@ -1,5 +1,5 @@ { - "ignorePaths": ["*.drawio", "*/**/CHANGELOG.rst", "external/lanelet2_matching/**", "*.xsd"], + "ignorePaths": ["*.drawio", "*/**/CHANGELOG.rst", "*.xsd"], "words": [ "ARGN", "AUTORCC", From f6fc2dbb71945a961b0f4660decab812b52b518c Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 1 Apr 2024 15:15:55 +0900 Subject: [PATCH 086/120] doc: update OpenSCENARIO definition annotation to OpenSCENARIO XML 1.3 --- .../syntax/deterministic.hpp | 20 ++++++------ ...rministic_multi_parameter_distribution.hpp | 20 ++++++------ ...stic_multi_parameter_distribution_type.hpp | 20 ++++++------ .../deterministic_parameter_distribution.hpp | 24 +++++++------- ...ministic_single_parameter_distribution.hpp | 22 +++++++------ ...tic_single_parameter_distribution_type.hpp | 24 +++++++------- .../syntax/distribution_definition.hpp | 22 +++++++------ .../syntax/distribution_range.hpp | 25 +++++++++------ .../syntax/distribution_set.hpp | 20 ++++++------ .../syntax/distribution_set_element.hpp | 16 ++++++---- .../syntax/histogram.hpp | 20 ++++++------ .../syntax/histogram_bin.hpp | 22 +++++++------ .../syntax/normal_distribution.hpp | 25 ++++++++------- .../syntax/parameter_assignment.hpp | 21 +++++++----- .../syntax/parameter_assignments.hpp | 8 ----- .../syntax/parameter_value_distribution.hpp | 23 +++++++------ ...arameter_value_distribution_definition.hpp | 20 ++++++------ .../syntax/parameter_value_set.hpp | 20 ++++++------ .../syntax/poisson_distribution.hpp | 22 +++++++------ .../syntax/probability_distribution_set.hpp | 20 ++++++------ .../probability_distribution_set_element.hpp | 18 ++++++----- .../openscenario_interpreter/syntax/range.hpp | 18 ++++++----- .../syntax/stochastic.hpp | 25 ++++++++------- .../syntax/stochastic_distribution.hpp | 22 +++++++------ .../syntax/stochastic_distribution_type.hpp | 32 +++++++++++-------- .../syntax/uniform_distribution.hpp | 20 ++++++------ .../syntax/user_defined_distribution.hpp | 25 ++++++++------- .../syntax/value_set_distribution.hpp | 20 ++++++------ 28 files changed, 323 insertions(+), 271 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp index 2d18656ef95..4d13538eced 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic.hpp @@ -24,15 +24,17 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- Deterministic 1.2 ------------------------------------------------------ - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + Deterministic (OpenSCENARIO XML 1.3) + + Top level container containing all deterministic distribution elements. + + + + + + +*/ struct Deterministic : public ParameterDistributionContainer { const std::list deterministic_parameter_distributions; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp index b9e241008d5..c1e53315858 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution.hpp @@ -23,15 +23,17 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- DeterministicMultiParameterDistribution 1.2 ---------------------------- - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + DeterministicMultiParameterDistribution (OpenSCENARIO XML 1.3) + + Container for a deterministic distribution which is applied to multiple parameters. + + + + + + +*/ struct DeterministicMultiParameterDistribution : public DeterministicMultiParameterDistributionType, public ParameterDistributionContainer { diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution_type.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution_type.hpp index 7449dbde838..89460a9230c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution_type.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_multi_parameter_distribution_type.hpp @@ -23,15 +23,17 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- DeterministicMultiParameterDistributionType 1.2 ------------------------ - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + DeterministicMultiParameterDistributionType (OpenSCENARIO XML 1.3) + + A deterministic distribution type which can be applied to multiple parameters. + + + + + + +*/ struct DeterministicMultiParameterDistributionType : public ValueSetDistribution { explicit DeterministicMultiParameterDistributionType(const pugi::xml_node &, Scope & scope); diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_parameter_distribution.hpp index abc81721d22..298de0d85a1 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_parameter_distribution.hpp @@ -24,18 +24,18 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- DeterministicParameterDistribution 1.2 --------------------------------- - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + DeterministicParameterDistribution (OpenSCENARIO XML 1.3) + + Either a DeterministicMultiParameterDistribution or a DeterministicSingleParameterDistribution + + + + + + + +*/ struct DeterministicParameterDistribution : public Group { explicit DeterministicParameterDistribution(const pugi::xml_node &, Scope & scope); diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp index cc783a9d325..5de8634cc07 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution.hpp @@ -23,16 +23,18 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- DeterministicSingleParameterDistribution 1.2 --------------------------- - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + DeterministicSingleParameterDistribution (OpenSCENARIO XML 1.3) + + Container for a deterministic distribution which is applied to a single parameter. + + + + + + + +*/ struct DeterministicSingleParameterDistribution : public DeterministicSingleParameterDistributionType, public ParameterDistributionContainer diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp index 1b091c5807e..868c9884526 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/deterministic_single_parameter_distribution_type.hpp @@ -26,17 +26,19 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- DeterministicSingleParameterDistributionType 1.2 ----------------------- - * - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + DeterministicSingleParameterDistributionType (OpenSCENARIO XML 1.3) + + A deterministic distribution type which can be applied to a single parameter. + + + + + + + + +*/ struct DeterministicSingleParameterDistributionType : public Group { explicit DeterministicSingleParameterDistributionType(const pugi::xml_node &, Scope & scope); diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_definition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_definition.hpp index 576fb1dbd12..b5c9994ff3b 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_definition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_definition.hpp @@ -24,16 +24,18 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- DistributionDefinition 1.2 --------------------------------------------- - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + DistributionDefinition (OpenSCENARIO XML 1.3) + + Indicates whether the content defines a deterministic or stochastic parameter distribution. + + + + + + + +*/ struct DistributionDefinition : public Group { explicit DistributionDefinition(const pugi::xml_node &, Scope & scope); diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp index d8ae87e1a20..7b508b20ddc 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_range.hpp @@ -24,16 +24,21 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- DistributionRange 1.2 -------------------------------------------------- - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ - +/* + DistributionRange (OpenSCENARIO XML 1.3) + + A range of values used for a deterministic distribution. + The range starts with lower limit, Each additional value is defined + by adding the step value to the previous value until the value is greater than upper limit. + Upper limit can be part of the range. + + + + + + + +*/ struct DistributionRange : private Scope, public ComplexType, public SingleParameterDistributionBase { const Double step_width; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp index 32db787204f..4f91ee05bba 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set.hpp @@ -22,15 +22,17 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- DistributionSet 1.2 ---------------------------------------------------- - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + DistributionSet (OpenSCENARIO XML 1.3) + + A set of possible values which can occur in a deterministic distribution. + + + + + + +*/ struct DistributionSet : private Scope, public ComplexType, public SingleParameterDistributionBase { diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set_element.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set_element.hpp index 36081c509d6..f8a9cb3b28d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set_element.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/distribution_set_element.hpp @@ -23,13 +23,15 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- DistributionSetElement 1.2 --------------------------------------------- - * - * - * - * - * - * ------------------------------------------------------------------------ */ +/* + DistributionSetElement (OpenSCENARIO XML 1.3) + + Indicates an element for a deterministic distribution. + + + + +*/ struct DistributionSetElement { const String value; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index 61480d69d31..43674227e1d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -24,15 +24,17 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- Histogram 1.2 ---------------------------------------------------------- - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + Histogram (OpenSCENARIO XML 1.3) + + Histogram which can be applied to a single parameter. + + + + + + +*/ struct Histogram : public ComplexType, private Scope, public StochasticParameterDistributionBase { diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram_bin.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram_bin.hpp index 218880763ab..3babd4ed866 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram_bin.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram_bin.hpp @@ -23,16 +23,18 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- HistogramBin 1.2 ------------------------------------------------------- - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + HistogramBin (OpenSCENARIO XML 1.3) + + A bin in a histogram. + + + + + + + +*/ struct HistogramBin : public ComplexType { const Range range; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp index df914527978..f1566582c4a 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/normal_distribution.hpp @@ -26,18 +26,19 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- NormalDistribution 1.2 ------------------------------------------------- - * - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ - +/* + NormalDistribution (OpenSCENARIO XML 1.3) + + Normal distribution which can be applied to a single parameter. + + + + + + + + +*/ struct NormalDistribution : public ComplexType, private Scope, public StochasticParameterDistributionBase diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_assignment.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_assignment.hpp index 68eac384053..8118a4b6f5f 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_assignment.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_assignment.hpp @@ -23,14 +23,19 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- ParameterAssignment-------------------------------------------------- - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + ParameterAssignment (OpenSCENARIO XML 1.3) + + Assignment of a value to a named parameter. It is either used when importing + types of vehicles, controllers etc. from a catalog during startup of a simulator. + It is also used when generating concrete scenarios from logical scenarios + with ParameterValueSets during runtime of a scenario generator. + + + + + +*/ struct ParameterAssignment { explicit ParameterAssignment(const pugi::xml_node & node, Scope & scope) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_assignments.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_assignments.hpp index bc5e6dbfdc8..dc18b13b9d0 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_assignments.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_assignments.hpp @@ -24,14 +24,6 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- ParameterAssignment-------------------------------------------------- - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ struct ParameterAssignments : std::list { explicit ParameterAssignments() = default; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp index 02127cd7e52..8bc021a368c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution.hpp @@ -22,16 +22,19 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- ParameterValueDistribution 1.2 ----------------------------------------- - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + ParameterValueDistribution (OpenSCENARIO XML 1.3) + + The ParameterValueDistribution represents + the top level container of a parameter distribution file. + + + + + + + +*/ struct ParameterValueDistribution : public DistributionDefinition, public ParameterDistributionContainer { diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution_definition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution_definition.hpp index 50b3ead719b..47c79289d37 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution_definition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_distribution_definition.hpp @@ -22,15 +22,17 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- ParameterValueDistributionDefinition 1.2 ------------------------------ - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + ParameterValueDistributionDefinition (OpenSCENARIO XML 1.3) + + A marker stating that the OpenSCENARIO file is a parameter value distribution. + + + + + + +*/ struct ParameterValueDistributionDefinition : public ParameterValueDistribution { explicit ParameterValueDistributionDefinition(const pugi::xml_node &, Scope &); diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp index 63b7f65d938..e4d436fa220 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/parameter_value_set.hpp @@ -21,15 +21,17 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- ParameterValueSet 1.2 -------------------------------------------------- - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + ParameterValueSet (OpenSCENARIO XML 1.3) + + Set of parameter values that have to be assigned for a single concrete scenario. + + + + + + +*/ struct ParameterValueSet : private Scope { const std::list parameter_assignments; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp index 744b668fde0..b4ac24a69b7 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/poisson_distribution.hpp @@ -25,16 +25,18 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- PoissonDistribution 1.2 ------------------------------------------------ - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + PoissonDistribution (OpenSCENARIO XML 1.3) + + Poisson distribution which can be applied to a single parameter. + + + + + + + +*/ struct PoissonDistribution : public ComplexType, private Scope, public StochasticParameterDistributionBase diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp index 9143f16d8bb..501c7c29352 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set.hpp @@ -23,15 +23,17 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- ProbabilityDistributionSet 1.2 ----------------------------------------- - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + ProbabilityDistributionSet (OpenSCENARIO XML 1.3) + + Container for a set of single values with a defined probability. + + + + + + +*/ struct ProbabilityDistributionSet : public ComplexType, private Scope, diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set_element.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set_element.hpp index b9d23e1a9d9..5132d7c7dbf 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set_element.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/probability_distribution_set_element.hpp @@ -23,14 +23,16 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- ProbabilityDistributionSetElement 1.2 ---------------------------------- - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + ProbabilityDistributionSetElement (OpenSCENARIO XML 1.3) + + Indicates a value and probability in a stochastic distribution. + + + + + +*/ struct ProbabilityDistributionSetElement : public ComplexType { const String value; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/range.hpp index 6a2eddf8b80..65e11824c11 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/range.hpp @@ -23,14 +23,16 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- Range 1.2 -------------------------------------------------------------- - * - * - * - * - * - * - * ------------------------------------------------------------------------ */ +/* + Range (OpenSCENARIO XML 1.3) + + Indicates a range for a distribution where the following rule applies: lowerLimit <= value <= upperLimit. + + + + + +*/ struct Range { const Double lower_limit = Double::infinity(); diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp index 55e63230b23..e291a2420f0 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic.hpp @@ -26,18 +26,19 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- Stochastic 1.2 --------------------------------------------------------- - * - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + Stochastic (OpenSCENARIO XML 1.3) + + Top level container for all stochastic distribution elements. + + + + + + + + +*/ struct Stochastic : public ComplexType, public ParameterDistributionContainer, private Scope { diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp index a35332d7ae5..722c44357c1 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution.hpp @@ -24,16 +24,18 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- StochasticDistribution 1.2 --------------------------------------------- - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + StochasticDistribution (OpenSCENARIO XML 1.3) + + Container for a stochastic distribution which applies to a single parameter. + + + + + + + +*/ struct StochasticDistribution : public StochasticDistributionType, public StochasticParameterDistributionBase { diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp index 0761e1e78bf..b7b5eccf249 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp @@ -28,20 +28,23 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- StochasticDistributionType 1.2 ----------------------------------------- - * - * - * - * - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + StochasticDistributionType (OpenSCENARIO XML 1.3) + + Container for a stochastic distribution type which can be applied to a single parameter. + + + + + + + + + + + + +*/ struct StochasticDistributionType : public Group { explicit StochasticDistributionType(const pugi::xml_node &, Scope & scope); @@ -51,6 +54,7 @@ DEFINE_LAZY_VISITOR( StochasticDistributionType, CASE(ProbabilityDistributionSet), // CASE(NormalDistribution), // + // CASE(LogNormalDistribution), // CASE(UniformDistribution), // CASE(PoissonDistribution), // CASE(Histogram), // diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp index 87bdebdfc59..fd6e42bf9a4 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/uniform_distribution.hpp @@ -25,15 +25,17 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- UniformDistribution 1.2 ------------------------------------------------ - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + UniformDistribution (OpenSCENARIO XML 1.3) + + Uniform distribution which can be applied to a single parameter. + + + + + + +*/ struct UniformDistribution : public ComplexType, private Scope, public StochasticParameterDistributionBase diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp index 6f8d552cfbd..d870fe6285c 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_distribution.hpp @@ -22,17 +22,20 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- UserDefinedDistribution 1.2 -------------------------------------------- - * - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + UserDefinedDistribution (OpenSCENARIO XML 1.3) + + Indicates a user defined distribution which can be deterministic or stochastic. + This distribution contains a property with the name type and some user defined content. + + + + + + + + +*/ struct UserDefinedDistribution : private Scope, public ComplexType { const String type; diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp index dfd9e605e68..296f07853f8 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/value_set_distribution.hpp @@ -23,15 +23,17 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- ValueSetDistribution 1.2 ----------------------------------------------- - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + ValueSetDistribution (OpenSCENARIO XML 1.3) + + Deterministic multi-parameter distribution, where one or multiple sets of parameter values can be defined. + + + + + + +*/ struct ValueSetDistribution : public Scope, public MultiParameterDistributionBase { const std::list parameter_value_sets; From 0dfb734b6cb73ba31dd9a620c9175e164482ce76 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 3 Apr 2024 18:21:17 +0900 Subject: [PATCH 087/120] feat(openscenario_interpreter): add LogNormalDistribution Signed-off-by: Kotaro Yoshimoto --- .../syntax/log_normal_distribution.hpp | 60 +++++++++++++++++++ .../syntax/stochastic_distribution_type.hpp | 4 +- .../src/syntax/log_normal_distribution.cpp | 36 +++++++++++ 3 files changed, 98 insertions(+), 2 deletions(-) create mode 100644 openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/log_normal_distribution.hpp create mode 100644 openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/log_normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/log_normal_distribution.hpp new file mode 100644 index 00000000000..1f38446195d --- /dev/null +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/log_normal_distribution.hpp @@ -0,0 +1,60 @@ +// 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__LOG_NORMAL_DISTRIBUTION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__LOG_NORMAL_DISTRIBUTION_HPP_ + +#include +#include +#include +#include +#include +#include + +namespace openscenario_interpreter +{ +inline namespace syntax +{ +/* + LogNormalDistribution (OpenSCENARIO XML 1.3) + + Defines a log normal distribution. + + + + + + + + +*/ +struct LogNormalDistribution : public ComplexType, + private Scope, + public StochasticParameterDistributionBase +{ + const Range range; + + const Double expected_value; + + const Double variance; + + std::lognormal_distribution distribute; + + explicit LogNormalDistribution(const pugi::xml_node &, Scope & scope); + + auto derive() -> Object override; +}; +} // namespace syntax +} // namespace openscenario_interpreter +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__LOG_NORMAL_DISTRIBUTION_HPP_ diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp index b7b5eccf249..33fec69811d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp @@ -54,10 +54,10 @@ DEFINE_LAZY_VISITOR( StochasticDistributionType, CASE(ProbabilityDistributionSet), // CASE(NormalDistribution), // - // CASE(LogNormalDistribution), // + CASE(LogNormalDistribution), // CASE(UniformDistribution), // CASE(PoissonDistribution), // - CASE(Histogram), // + CASE(Histogram) // // CASE(UserDefinedDistribution), // ); } // namespace syntax diff --git a/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp new file mode 100644 index 00000000000..ad16b34d004 --- /dev/null +++ b/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp @@ -0,0 +1,36 @@ +// 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 + +namespace openscenario_interpreter +{ +inline namespace syntax +{ +LogNormalDistribution::LogNormalDistribution( + const pugi::xml_node & node, openscenario_interpreter::Scope & scope) +: Scope(scope), + range(readElement("Range", node, scope)), + expected_value(readAttribute("expectedValue", node, scope)), + variance(readAttribute("variance", node, scope)), + distribute( + static_cast(expected_value.data), sta::sqrt(static_cast(variance.data))) +{ +} + +auto LogNormalDistribution::derive() -> Object { return make(distribute(random_engine)); } +} // namespace syntax +} // namespace openscenario_interpreter From 35833b70c26ba40953f81e776697a71c0a7c6fe2 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 3 Apr 2024 18:40:26 +0900 Subject: [PATCH 088/120] fix(openscenario_interpreter): fix wrong initialization for NormalDistribution Signed-off-by: Kotaro Yoshimoto --- .../src/syntax/normal_distribution.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp index 690402daa28..56deadfdbf5 100644 --- a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include @@ -25,7 +26,8 @@ NormalDistribution::NormalDistribution( range(readElement("Range", node, scope)), expected_value(readAttribute("expectedValue", node, scope)), variance(readAttribute("variance", node, scope)), - distribute(static_cast(expected_value.data), static_cast(variance.data)) + distribute( + static_cast(expected_value.data), std::sqrt(static_cast(variance.data))) { } From 02a095454856b09f8081ecaa0dcea294bbc5b51d Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 5 Apr 2024 18:45:12 +0900 Subject: [PATCH 089/120] fix: compile error on LogNormalDistribution Signed-off-by: Kotaro Yoshimoto --- .../syntax/stochastic_distribution_type.hpp | 1 + .../src/syntax/log_normal_distribution.cpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp index 33fec69811d..6bae5544653 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/stochastic_distribution_type.hpp @@ -17,6 +17,7 @@ #include #include +#include #include #include #include diff --git a/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp index ad16b34d004..3861c83011d 100644 --- a/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp @@ -27,7 +27,7 @@ LogNormalDistribution::LogNormalDistribution( expected_value(readAttribute("expectedValue", node, scope)), variance(readAttribute("variance", node, scope)), distribute( - static_cast(expected_value.data), sta::sqrt(static_cast(variance.data))) + static_cast(expected_value.data), std::sqrt(static_cast(variance.data))) { } From 89313d525219d11aee5c7049dc7526d476a64a50 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 10 Apr 2024 17:26:03 +0900 Subject: [PATCH 090/120] fix: preprocessor node name Signed-off-by: Kotaro Yoshimoto --- .../src/openscenario_preprocessor_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp index dfeed705912..dd2f847fa95 100644 --- a/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp +++ b/openscenario/openscenario_preprocessor/src/openscenario_preprocessor_node.cpp @@ -24,7 +24,7 @@ class PreprocessorNode : public rclcpp::Node, public openscenario_preprocessor:: { public: explicit PreprocessorNode(const rclcpp::NodeOptions & options) - : rclcpp::Node("preprocessor", options), + : rclcpp::Node("openscenario_preprocessor", options), openscenario_preprocessor::Preprocessor([this] { declare_parameter("output_directory", "/tmp/openscenario_preprocessor"); return get_parameter("output_directory").as_string(); From 53294c9061c1b157aa0bd398ac894a0004517b40 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 10 Apr 2024 17:30:41 +0900 Subject: [PATCH 091/120] chore: ignore lognormal on cspell Signed-off-by: Kotaro Yoshimoto --- .../openscenario_interpreter/syntax/log_normal_distribution.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/log_normal_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/log_normal_distribution.hpp index 1f38446195d..1f211e304f4 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/log_normal_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/log_normal_distribution.hpp @@ -22,6 +22,8 @@ #include #include +// cspell: ignore lognormal + namespace openscenario_interpreter { inline namespace syntax From 02a2a5a6429c5c37ff55e343c3a8bad36dc5afa0 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 10 Apr 2024 17:53:12 +0900 Subject: [PATCH 092/120] chore: update openscenario_validator version Signed-off-by: Kotaro Yoshimoto --- openscenario/openscenario_validator/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 5e4a4ccf1ac..a932b098088 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 0.6.7 + 1.12.0 Validator for OpenSCENARIO 1.2 Kotaro Yoshimoto Apache License 2.0 From fe527be397fc2a00adc5c6bdbc28d58ac8cd6da8 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 10 Apr 2024 18:41:35 +0900 Subject: [PATCH 093/120] feat: update OpenSCENARIO version for openscenario_validator Signed-off-by: Kotaro Yoshimoto --- .../openscenario_validator/CMakeLists.txt | 4 +- .../configure/OpenSCENARIO-1.3.xsd | 2603 +++++++++++++++++ .../configure/schema.cpp | 2 +- .../openscenario_validator/validator.hpp | 2 +- .../openscenario_validator/package.xml | 2 +- 5 files changed, 2608 insertions(+), 5 deletions(-) create mode 100644 openscenario/openscenario_validator/configure/OpenSCENARIO-1.3.xsd diff --git a/openscenario/openscenario_validator/CMakeLists.txt b/openscenario/openscenario_validator/CMakeLists.txt index 14a206747a9..7a89fd6ae57 100644 --- a/openscenario/openscenario_validator/CMakeLists.txt +++ b/openscenario/openscenario_validator/CMakeLists.txt @@ -1,11 +1,11 @@ cmake_minimum_required(VERSION 3.16.3) # Ubuntu 20.04 default CMake version -project(openscenario_validator VERSION 0.0.0) +project(openscenario_validator) find_package(ament_cmake_auto REQUIRED) find_package(XercesC REQUIRED) -file(READ ${CMAKE_CURRENT_SOURCE_DIR}/configure/OpenSCENARIO-1.2.xsd ${PROJECT_NAME}_OPENSCENARIO_1_2_XSD) +file(READ ${CMAKE_CURRENT_SOURCE_DIR}/configure/OpenSCENARIO-1.3.xsd ${PROJECT_NAME}_OPENSCENARIO_1_3_XSD) configure_file(${CMAKE_CURRENT_SOURCE_DIR}/configure/schema.cpp ${CMAKE_CURRENT_SOURCE_DIR}/src/schema.cpp) diff --git a/openscenario/openscenario_validator/configure/OpenSCENARIO-1.3.xsd b/openscenario/openscenario_validator/configure/OpenSCENARIO-1.3.xsd new file mode 100644 index 00000000000..9c826e47351 --- /dev/null +++ b/openscenario/openscenario_validator/configure/OpenSCENARIO-1.3.xsd @@ -0,0 +1,2603 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + deprecated + + + + + + + + + + + + + + + + + + + deprecated + + + deprecated + + + deprecated + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + deprecated + + + + + + + + + + + + + + + deprecated + + + deprecated + + + deprecated + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + deprecated + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + deprecated + + + + + + + deprecated + + + + + + + + + + deprecated + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + + + + + + + + diff --git a/openscenario/openscenario_validator/configure/schema.cpp b/openscenario/openscenario_validator/configure/schema.cpp index 4330aa265a1..9b99cd92129 100644 --- a/openscenario/openscenario_validator/configure/schema.cpp +++ b/openscenario/openscenario_validator/configure/schema.cpp @@ -16,5 +16,5 @@ namespace openscenario_validator { -const std::string_view schema = R"###(${${PROJECT_NAME}_OPENSCENARIO_1_2_XSD})###"; +const std::string_view schema = R"###(${${PROJECT_NAME}_OPENSCENARIO_1_3_XSD})###"; } // namespace openscenario_validator diff --git a/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp b/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp index ac1cacfbd6d..365dae575c5 100644 --- a/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp +++ b/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp @@ -75,7 +75,7 @@ class OpenSCENARIOValidator ErrorHandler error_handler; - static constexpr auto schema_filepath = "/tmp/OpenSCENARIO-1.2.xsd"; + static constexpr auto schema_filepath = "/tmp/OpenSCENARIO-1.3.xsd"; public: explicit OpenSCENARIOValidator() diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index a932b098088..92cb834bf35 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -3,7 +3,7 @@ openscenario_validator 1.12.0 - Validator for OpenSCENARIO 1.2 + Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 ament_cmake_auto From 99b1b313e182fe513bde8db9790a0d962be1e24e Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 17 Apr 2024 19:07:09 +0900 Subject: [PATCH 094/120] doc: add sample scenario for LogNormalDistribution --- .../scenario/Stochastic.LogNormalDistribution.xosc | 14 ++++++++++++++ 1 file changed, 14 insertions(+) create mode 100644 test_runner/scenario_test_runner/scenario/Stochastic.LogNormalDistribution.xosc diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.LogNormalDistribution.xosc b/test_runner/scenario_test_runner/scenario/Stochastic.LogNormalDistribution.xosc new file mode 100644 index 00000000000..516111b2e14 --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/Stochastic.LogNormalDistribution.xosc @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + From 9823292ebf17f0cfa36c62e271c274ccb97e364f Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 18 Apr 2024 20:51:57 +0900 Subject: [PATCH 095/120] refactor: move parameter value distribution files --- .../Deterministic.DistributionRange.xosc | 2 +- .../Deterministic.DistributionSet.xosc | 2 +- .../Deterministic.ValueSetDistribution.xosc | 2 +- .../parameter_value_distribution}/Stochastic.Histogram.xosc | 2 +- .../Stochastic.LogNormalDistribution.xosc | 2 +- .../Stochastic.NormalDistribution.xosc | 2 +- .../Stochastic.PoissonDistribution.xosc | 2 +- .../Stochastic.ProbabilityDistributionSet.xosc | 2 +- .../Stochastic.UniformDistribution.xosc | 2 +- .../test/parameter_value_distribution}/sample.xosc | 0 10 files changed, 9 insertions(+), 9 deletions(-) rename {test_runner/scenario_test_runner/scenario => openscenario/openscenario_interpreter/test/parameter_value_distribution}/Deterministic.DistributionRange.xosc (80%) rename {test_runner/scenario_test_runner/scenario => openscenario/openscenario_interpreter/test/parameter_value_distribution}/Deterministic.DistributionSet.xosc (81%) rename {test_runner/scenario_test_runner/scenario => openscenario/openscenario_interpreter/test/parameter_value_distribution}/Deterministic.ValueSetDistribution.xosc (82%) rename {test_runner/scenario_test_runner/scenario => openscenario/openscenario_interpreter/test/parameter_value_distribution}/Stochastic.Histogram.xosc (84%) rename {test_runner/scenario_test_runner/scenario => openscenario/openscenario_interpreter/test/parameter_value_distribution}/Stochastic.LogNormalDistribution.xosc (79%) rename {test_runner/scenario_test_runner/scenario => openscenario/openscenario_interpreter/test/parameter_value_distribution}/Stochastic.NormalDistribution.xosc (79%) rename {test_runner/scenario_test_runner/scenario => openscenario/openscenario_interpreter/test/parameter_value_distribution}/Stochastic.PoissonDistribution.xosc (79%) rename {test_runner/scenario_test_runner/scenario => openscenario/openscenario_interpreter/test/parameter_value_distribution}/Stochastic.ProbabilityDistributionSet.xosc (81%) rename {test_runner/scenario_test_runner/scenario => openscenario/openscenario_interpreter/test/parameter_value_distribution}/Stochastic.UniformDistribution.xosc (78%) rename {test_runner/scenario_test_runner/scenario => openscenario/openscenario_interpreter/test/parameter_value_distribution}/sample.xosc (100%) diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.DistributionRange.xosc similarity index 80% rename from test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc rename to openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.DistributionRange.xosc index e66c305be01..4463e25a4ac 100644 --- a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionRange.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.DistributionRange.xosc @@ -2,7 +2,7 @@ - + diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.DistributionSet.xosc similarity index 81% rename from test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc rename to openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.DistributionSet.xosc index 3da621c7659..900551807d3 100644 --- a/test_runner/scenario_test_runner/scenario/Deterministic.DistributionSet.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.DistributionSet.xosc @@ -2,7 +2,7 @@ - + diff --git a/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.ValueSetDistribution.xosc similarity index 82% rename from test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc rename to openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.ValueSetDistribution.xosc index 2cdef8ff1f8..3c053ea0fcd 100644 --- a/test_runner/scenario_test_runner/scenario/Deterministic.ValueSetDistribution.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.ValueSetDistribution.xosc @@ -1,7 +1,7 @@ - + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.Histogram.xosc similarity index 84% rename from test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc rename to openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.Histogram.xosc index 134adfd9d6f..57546eea330 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.Histogram.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.Histogram.xosc @@ -2,7 +2,7 @@ - + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.LogNormalDistribution.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.LogNormalDistribution.xosc similarity index 79% rename from test_runner/scenario_test_runner/scenario/Stochastic.LogNormalDistribution.xosc rename to openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.LogNormalDistribution.xosc index 516111b2e14..4ba901e3d45 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.LogNormalDistribution.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.LogNormalDistribution.xosc @@ -2,7 +2,7 @@ - + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.NormalDistribution.xosc similarity index 79% rename from test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc rename to openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.NormalDistribution.xosc index 4c09f113523..1f46ec69d76 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.NormalDistribution.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.NormalDistribution.xosc @@ -2,7 +2,7 @@ - + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.PoissonDistribution.xosc similarity index 79% rename from test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc rename to openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.PoissonDistribution.xosc index cbcad3c3226..2a8a702dc01 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.PoissonDistribution.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.PoissonDistribution.xosc @@ -2,7 +2,7 @@ - + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.ProbabilityDistributionSet.xosc similarity index 81% rename from test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc rename to openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.ProbabilityDistributionSet.xosc index 0382e569c8b..2121fb3922f 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.ProbabilityDistributionSet.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.ProbabilityDistributionSet.xosc @@ -2,7 +2,7 @@ - + diff --git a/test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.UniformDistribution.xosc similarity index 78% rename from test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc rename to openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.UniformDistribution.xosc index 72e59bd92cb..933394612e5 100644 --- a/test_runner/scenario_test_runner/scenario/Stochastic.UniformDistribution.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.UniformDistribution.xosc @@ -2,7 +2,7 @@ - + diff --git a/test_runner/scenario_test_runner/scenario/sample.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/sample.xosc similarity index 100% rename from test_runner/scenario_test_runner/scenario/sample.xosc rename to openscenario/openscenario_interpreter/test/parameter_value_distribution/sample.xosc From 9ead47ce36e5f463946298c5c480ab855add6b88 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 18 Apr 2024 20:52:31 +0900 Subject: [PATCH 096/120] feat: add test for DistributionRange --- .../openscenario_interpreter/CMakeLists.txt | 6 + .../openscenario_interpreter/package.xml | 2 + .../test_parameter_value_distribution.cpp | 177 ++++++++++++++++++ 3 files changed, 185 insertions(+) create mode 100644 openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp diff --git a/openscenario/openscenario_interpreter/CMakeLists.txt b/openscenario/openscenario_interpreter/CMakeLists.txt index 9dd1ec6dd24..4a5da8a9d90 100644 --- a/openscenario/openscenario_interpreter/CMakeLists.txt +++ b/openscenario/openscenario_interpreter/CMakeLists.txt @@ -47,6 +47,10 @@ install( FILES ${CMAKE_CURRENT_SOURCE_DIR}/features DESTINATION lib/${PROJECT_NAME}) +install( + DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/test + DESTINATION share/${PROJECT_NAME}) + # ------------------------------------------------------------------------------ # test # ------------------------------------------------------------------------------ @@ -55,7 +59,9 @@ if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() ament_add_gtest(test_syntax test/test_syntax.cpp) + ament_add_gtest(test_parameter_value_distribution test/test_parameter_value_distribution.cpp) target_link_libraries(test_syntax ${PROJECT_NAME}) + target_link_libraries(test_parameter_value_distribution ${PROJECT_NAME}) endif() ament_auto_package() diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 301de7ee4e7..3fcfc94d8bd 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -26,6 +26,7 @@ tier4_simulation_msgs traffic_simulator traffic_simulator_msgs + ament_index_cpp ament_cmake_clang_format ament_cmake_copyright @@ -33,6 +34,7 @@ ament_cmake_pep257 ament_cmake_xmllint ament_lint_auto + ament_index_cpp ament_cmake diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp new file mode 100644 index 00000000000..f37521b3d51 --- /dev/null +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -0,0 +1,177 @@ +// 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 +#include +#include +#include +#include +#include + +TEST(syntax, dummy) { ASSERT_TRUE(true); } + +using openscenario_interpreter::OpenScenario; +using openscenario_interpreter::ParameterDistribution; +using openscenario_interpreter::ParameterValueDistribution; +using openscenario_interpreter::ParameterValueDistributionDefinition; + +class ParameterValueDistributionTester +{ +public: + explicit ParameterValueDistributionTester(std::string path) : script{path} + { + OpenScenario script{path}; + } + void check(const ParameterDistribution & expected) + { + auto & parameter_value_distribution = script.category.as(); + ParameterDistribution derived_distribution = parameter_value_distribution.derive(); + EXPECT_EQ(expected.size(), derived_distribution.size()); + + for (std::size_t i = 0; i < expected.size(); i++) { + const auto & expected_parameter_list = expected.at(i); + const auto & derived_parameter_list = derived_distribution.at(i); + EXPECT_EQ(expected_parameter_list->size(), derived_parameter_list->size()); + for (const auto & expected_parameter : *expected_parameter_list) { + const auto & derived_parameter = derived_parameter_list->at(expected_parameter.first); + EXPECT_EQ(expected_parameter.second, derived_parameter); + } + } + } + +private: + OpenScenario script; +}; + +TEST(ParameterValueDistribution, DistributionRange) +{ + using ament_index_cpp::get_package_share_directory; + + std::string path = get_package_share_directory("openscenario_interpreter") + + "/test/parameter_value_distribution/Deterministic.DistributionRange.xosc"; + + ParameterValueDistributionTester tester{path}; + + ParameterDistribution expected_distribution; + { + auto parameter_list = std::make_shared(); + (*parameter_list)["offset"] = + openscenario_interpreter::make(-1.0); + expected_distribution.emplace_back(parameter_list); + } + { + auto parameter_list = std::make_shared(); + (*parameter_list)["offset"] = + openscenario_interpreter::make(0.0); + expected_distribution.emplace_back(parameter_list); + } + { + auto parameter_list = std::make_shared(); + (*parameter_list)["offset"] = + openscenario_interpreter::make(1.0); + expected_distribution.emplace_back(parameter_list); + } + tester.check(expected_distribution); +} +// +// TEST(Error, Success) +// { +// using ament_index_cpp::get_package_share_directory; +// +// auto node { +// std::make_shared("", rclcpp::NodeOptions()) +// }; +// +// openscenario_interpreter::OpenScenario evaluate { +// get_package_share_directory("openscenario_interpreter") + "/test/success.xosc", +// node +// }; +// +// ASSERT_FALSE(evaluate.complete()); +// +// const auto begin {std::chrono::high_resolution_clock::now()}; +// +// using std::chrono_literals::operator""ms; +// +// rclcpp::WallRate rate {50ms}; +// +// using openscenario_interpreter::complete_state; +// +// for (evaluate.init(); evaluate() != complete_state; rate.sleep()) { +// ASSERT_LT( +// std::chrono::duration_cast( +// std::chrono::high_resolution_clock::now() - begin).count(), +// 20); +// } +// } + +// TEST(Syntax, invalid) +// { +// auto f = []() +// { +// openscenario_interpreter::OpenSCENARIO osc { XOSC("invalid-1.xosc") }; +// }; +// +// EXPECT_THROW({ f(); }, openscenario_interpreter::SyntaxError); +// } + +// TEST(Syntax, scenarioDefinition) +// { +// using namespace openscenario_interpreter; +// +// OpenSCENARIO osc { XOSC("example.xosc"), "127.0.0.1", 5555 }; +// +// // EXPECT_TRUE(osc.element("FileHeader")); +// // EXPECT_TRUE(osc.element("ParameterDeclarations")); +// +// // EXPECT_EQ(osc["FileHeader"].revMajor(), 1); +// // EXPECT_TRUE(osc.catalog_locations); +// // EXPECT_TRUE(osc.entities); +// // EXPECT_TRUE(osc.parameter_declarations); +// // EXPECT_TRUE(osc.road_network); +// // EXPECT_TRUE(osc.storyboard); +// +// EXPECT_TRUE(osc.evaluate().is()); +// } + +// TEST(Core, objectBinder) +// { +// using openscenario_interpreter::make; +// +// const auto foo {make(3.14)}; +// +// const auto result {foo.evaluate()}; +// +// EXPECT_TRUE(result.is()); +// EXPECT_TRUE(result.as().data = 3.14); +// } + +// TEST(Scenario, LaneChange) +// { +// using namespace openscenario_interpreter; +// +// OpenSCENARIO osc { XOSC("lane_change.xosc"), "127.0.0.1", 5555 }; +// } + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + + return RUN_ALL_TESTS(); +} From 948765e1f9324384dc7c29be724c642ac2d87a65 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 19 Apr 2024 16:12:21 +0900 Subject: [PATCH 097/120] feat: add test for deterministic distributions --- .../test_parameter_value_distribution.cpp | 122 ++++++++++++------ 1 file changed, 80 insertions(+), 42 deletions(-) diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp index f37521b3d51..d82798b528c 100644 --- a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -31,64 +31,102 @@ using openscenario_interpreter::ParameterDistribution; using openscenario_interpreter::ParameterValueDistribution; using openscenario_interpreter::ParameterValueDistributionDefinition; -class ParameterValueDistributionTester +void checkParameterValueDistribution(const std::string path, const ParameterDistribution & expected) { -public: - explicit ParameterValueDistributionTester(std::string path) : script{path} - { - OpenScenario script{path}; - } - void check(const ParameterDistribution & expected) - { - auto & parameter_value_distribution = script.category.as(); - ParameterDistribution derived_distribution = parameter_value_distribution.derive(); - EXPECT_EQ(expected.size(), derived_distribution.size()); - - for (std::size_t i = 0; i < expected.size(); i++) { - const auto & expected_parameter_list = expected.at(i); - const auto & derived_parameter_list = derived_distribution.at(i); - EXPECT_EQ(expected_parameter_list->size(), derived_parameter_list->size()); - for (const auto & expected_parameter : *expected_parameter_list) { - const auto & derived_parameter = derived_parameter_list->at(expected_parameter.first); - EXPECT_EQ(expected_parameter.second, derived_parameter); + OpenScenario script{path}; + auto actual = script.category.as().derive(); + EXPECT_EQ(expected.size(), actual.size()); + + for (std::size_t i = 0; i < expected.size(); i++) { + const auto & expected_parameter_list = expected.at(i); + const auto & actual_parameter_list = actual.at(i); + EXPECT_EQ(expected_parameter_list->size(), actual_parameter_list->size()); + for (const auto & [expected_parameter_name, expected_parameter] : *expected_parameter_list) { + const auto & actual_parameter = actual_parameter_list->at(expected_parameter_name); + using openscenario_interpreter::Boolean; + using openscenario_interpreter::Double; + using openscenario_interpreter::Integer; + using openscenario_interpreter::String; + using openscenario_interpreter::UnsignedInt; + using openscenario_interpreter::UnsignedShort; + if (expected_parameter.is()) { + EXPECT_EQ(expected_parameter.as(), actual_parameter.as()); + } else if (expected_parameter.is()) { + EXPECT_EQ(expected_parameter.as(), actual_parameter.as()); + } else if (expected_parameter.is()) { + EXPECT_EQ(expected_parameter.as(), actual_parameter.as()); + } else if (expected_parameter.is()) { + EXPECT_EQ(expected_parameter.as(), actual_parameter.as()); + } else if (expected_parameter.is()) { + EXPECT_EQ(expected_parameter.as(), actual_parameter.as()); + } else if (expected_parameter.is()) { + EXPECT_EQ(expected_parameter.as(), actual_parameter.as()); + } else { + THROW_SYNTAX_ERROR(std::quoted(expected_parameter_name), "is unexpected type"); } } } +} -private: - OpenScenario script; -}; +template +auto makeParameterListSharedPtr(const std::string & name, U value) +{ + auto parameter_list = std::make_shared(); + (*parameter_list)[name] = openscenario_interpreter::make(value); + return parameter_list; +} TEST(ParameterValueDistribution, DistributionRange) { using ament_index_cpp::get_package_share_directory; + using openscenario_interpreter::Double; std::string path = get_package_share_directory("openscenario_interpreter") + "/test/parameter_value_distribution/Deterministic.DistributionRange.xosc"; - ParameterValueDistributionTester tester{path}; + ParameterDistribution expected_distribution; + expected_distribution.push_back(makeParameterListSharedPtr("offset", -1.0)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.0)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 1.0)); + + checkParameterValueDistribution(path, expected_distribution); +} + +TEST(ParameterValueDistribution, DistributionSet) +{ + using ament_index_cpp::get_package_share_directory; + using openscenario_interpreter::String; + + std::string path = get_package_share_directory("openscenario_interpreter") + + "/test/parameter_value_distribution/Deterministic.DistributionSet.xosc"; ParameterDistribution expected_distribution; - { - auto parameter_list = std::make_shared(); - (*parameter_list)["offset"] = - openscenario_interpreter::make(-1.0); - expected_distribution.emplace_back(parameter_list); - } - { - auto parameter_list = std::make_shared(); - (*parameter_list)["offset"] = - openscenario_interpreter::make(0.0); - expected_distribution.emplace_back(parameter_list); - } - { - auto parameter_list = std::make_shared(); - (*parameter_list)["offset"] = - openscenario_interpreter::make(1.0); - expected_distribution.emplace_back(parameter_list); - } - tester.check(expected_distribution); + expected_distribution.push_back(makeParameterListSharedPtr("LANE_ID", "34510")); + expected_distribution.push_back(makeParameterListSharedPtr("LANE_ID", "34513")); + expected_distribution.push_back(makeParameterListSharedPtr("LANE_ID", "34564")); + + checkParameterValueDistribution(path, expected_distribution); } + +TEST(ParameterValueDistribution, ValueSetDistribution) +{ + using ament_index_cpp::get_package_share_directory; + using openscenario_interpreter::Double; + using openscenario_interpreter::String; + using openscenario_interpreter::make; + + std::string path = get_package_share_directory("openscenario_interpreter") + + "/test/parameter_value_distribution/Deterministic.ValueSetDistribution.xosc"; + + ParameterDistribution expected_distribution; + auto parameter_list = std::make_shared(); + (*parameter_list)["LANE_ID"] = make("34564"); + (*parameter_list)["offset"] = make("1.0"); + expected_distribution.push_back(parameter_list); + + checkParameterValueDistribution(path, expected_distribution); +} + // // TEST(Error, Success) // { From 87e92cf37fb4bcf1a28b8bb788597577f4aa3c2a Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 19 Apr 2024 18:12:21 +0900 Subject: [PATCH 098/120] feat: add tests for stochastic distributions --- .../src/syntax/log_normal_distribution.cpp | 2 +- .../syntax/stochastic_distribution_type.cpp | 1 + .../Stochastic.LogNormalDistribution.xosc | 2 +- .../Stochastic.PoissonDistribution.xosc | 2 +- .../test_parameter_value_distribution.cpp | 105 +++++++++++++++++- .../openscenario_validator/CMakeLists.txt | 3 + 6 files changed, 110 insertions(+), 5 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp index 3861c83011d..57a254590b7 100644 --- a/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp @@ -31,6 +31,6 @@ LogNormalDistribution::LogNormalDistribution( { } -auto LogNormalDistribution::derive() -> Object { return make(distribute(random_engine)); } +auto LogNormalDistribution::derive() -> Object { return make(range.evaluate(distribute(random_engine))); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution_type.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution_type.cpp index 4f2d334ae5b..62f068c5289 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution_type.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic_distribution_type.cpp @@ -24,6 +24,7 @@ StochasticDistributionType::StochasticDistributionType(const pugi::xml_node & no : Group( choice(node, std::make_pair("ProbabilityDistributionSet", [&](auto && node){return make(node, scope);}), + std::make_pair("LogNormalDistribution", [&](auto && node){return make(node, scope);}), std::make_pair("NormalDistribution", [&](auto && node){return make(node, scope);}), std::make_pair("UniformDistribution", [&](auto && node){return make(node, scope);}), std::make_pair("PoissonDistribution", [&](auto && node){return make(node, scope);}), diff --git a/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.LogNormalDistribution.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.LogNormalDistribution.xosc index 4ba901e3d45..fa30d31f18e 100644 --- a/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.LogNormalDistribution.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.LogNormalDistribution.xosc @@ -5,7 +5,7 @@ - + diff --git a/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.PoissonDistribution.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.PoissonDistribution.xosc index 2a8a702dc01..8a5aadff8b8 100644 --- a/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.PoissonDistribution.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.PoissonDistribution.xosc @@ -5,7 +5,7 @@ - + diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp index d82798b528c..95d5f91e1dc 100644 --- a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -111,9 +111,8 @@ TEST(ParameterValueDistribution, DistributionSet) TEST(ParameterValueDistribution, ValueSetDistribution) { using ament_index_cpp::get_package_share_directory; - using openscenario_interpreter::Double; - using openscenario_interpreter::String; using openscenario_interpreter::make; + using openscenario_interpreter::String; std::string path = get_package_share_directory("openscenario_interpreter") + "/test/parameter_value_distribution/Deterministic.ValueSetDistribution.xosc"; @@ -127,6 +126,108 @@ TEST(ParameterValueDistribution, ValueSetDistribution) checkParameterValueDistribution(path, expected_distribution); } +// Histogram +TEST(ParameterValueDistribution, Histogram) +{ + using ament_index_cpp::get_package_share_directory; + using openscenario_interpreter::Double; + + std::string path = get_package_share_directory("openscenario_interpreter") + + "/test/parameter_value_distribution/Stochastic.Histogram.xosc"; + + ParameterDistribution expected_distribution; + expected_distribution.push_back(makeParameterListSharedPtr("offset", -0.657155383483317367954157361964)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", -0.122937022973606868703200234449)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", -0.068217520040680490467366325902)); + + checkParameterValueDistribution(path, expected_distribution); +} + +TEST(ParameterValueDistribution, LogNormalDistribution) +{ + using ament_index_cpp::get_package_share_directory; + using openscenario_interpreter::Double; + + std::string path = get_package_share_directory("openscenario_interpreter") + + "/test/parameter_value_distribution/Stochastic.LogNormalDistribution.xosc"; + + ParameterDistribution expected_distribution; + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.0)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.0)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.0)); + + checkParameterValueDistribution(path, expected_distribution); +} + +TEST(ParameterValueDistribution, NormalDistribution) +{ + using ament_index_cpp::get_package_share_directory; + using openscenario_interpreter::Double; + + std::string path = get_package_share_directory("openscenario_interpreter") + + "/test/parameter_value_distribution/Stochastic.NormalDistribution.xosc"; + + ParameterDistribution expected_distribution; + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.793935916513793027426970638771)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.214115627062221924870044631461)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.050105047474801357731966078290)); + + checkParameterValueDistribution(path, expected_distribution); +} + +// PoissonDistribution +TEST(ParameterValueDistribution, PoissonDistribution) +{ + using ament_index_cpp::get_package_share_directory; + using openscenario_interpreter::Double; + using openscenario_interpreter::make; + using openscenario_interpreter::String; + + std::string path = get_package_share_directory("openscenario_interpreter") + + "/test/parameter_value_distribution/Stochastic.PoissonDistribution.xosc"; + + ParameterDistribution expected_distribution; + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.0)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 1.0)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 1.0)); + + checkParameterValueDistribution(path, expected_distribution); +} + +// ProbabilityDistribution +TEST(ParameterValueDistribution, ProbabilityDistributionSet) +{ + using ament_index_cpp::get_package_share_directory; + using openscenario_interpreter::String; + + std::string path = get_package_share_directory("openscenario_interpreter") + + "/test/parameter_value_distribution/Stochastic.ProbabilityDistributionSet.xosc"; + + ParameterDistribution expected_distribution; + expected_distribution.push_back(makeParameterListSharedPtr("offset", "0.0")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "1.0")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "1.0")); + + checkParameterValueDistribution(path, expected_distribution); +} + +// UniformDistribution +TEST(ParameterValueDistribution, UniformDistribution) +{ + using ament_index_cpp::get_package_share_directory; + using openscenario_interpreter::Double; + + std::string path = get_package_share_directory("openscenario_interpreter") + + "/test/parameter_value_distribution/Stochastic.UniformDistribution.xosc"; + + ParameterDistribution expected_distribution; + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.185689233033365264091685276071)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.688531488513196565648399882775)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.715891239979659754766316837049)); + + checkParameterValueDistribution(path, expected_distribution); +} + // // TEST(Error, Success) // { diff --git a/openscenario/openscenario_validator/CMakeLists.txt b/openscenario/openscenario_validator/CMakeLists.txt index aaae0e92997..5e2b19f3047 100644 --- a/openscenario/openscenario_validator/CMakeLists.txt +++ b/openscenario/openscenario_validator/CMakeLists.txt @@ -36,4 +36,7 @@ install(TARGETS ${PROJECT_NAME} install(TARGETS validator DESTINATION lib/${PROJECT_NAME}) +ament_export_include_directories(include) +ament_export_libraries(${PROJECT_NAME}) + ament_package() From b800686452fb815595a3634370f7ff431e4ce00a Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 19 Apr 2024 18:12:55 +0900 Subject: [PATCH 099/120] chore: apply linter --- .../src/syntax/log_normal_distribution.cpp | 5 ++- .../test_parameter_value_distribution.cpp | 32 ++++++++++++------- 2 files changed, 25 insertions(+), 12 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp index 57a254590b7..071ecb50e30 100644 --- a/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp @@ -31,6 +31,9 @@ LogNormalDistribution::LogNormalDistribution( { } -auto LogNormalDistribution::derive() -> Object { return make(range.evaluate(distribute(random_engine))); } +auto LogNormalDistribution::derive() -> Object +{ + return make(range.evaluate(distribute(random_engine))); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp index 95d5f91e1dc..2dd886238eb 100644 --- a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -136,9 +136,12 @@ TEST(ParameterValueDistribution, Histogram) "/test/parameter_value_distribution/Stochastic.Histogram.xosc"; ParameterDistribution expected_distribution; - expected_distribution.push_back(makeParameterListSharedPtr("offset", -0.657155383483317367954157361964)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", -0.122937022973606868703200234449)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", -0.068217520040680490467366325902)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", -0.657155383483317367954157361964)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", -0.122937022973606868703200234449)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", -0.068217520040680490467366325902)); checkParameterValueDistribution(path, expected_distribution); } @@ -168,9 +171,12 @@ TEST(ParameterValueDistribution, NormalDistribution) "/test/parameter_value_distribution/Stochastic.NormalDistribution.xosc"; ParameterDistribution expected_distribution; - expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.793935916513793027426970638771)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.214115627062221924870044631461)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.050105047474801357731966078290)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.793935916513793027426970638771)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.214115627062221924870044631461)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.050105047474801357731966078290)); checkParameterValueDistribution(path, expected_distribution); } @@ -200,8 +206,9 @@ TEST(ParameterValueDistribution, ProbabilityDistributionSet) using ament_index_cpp::get_package_share_directory; using openscenario_interpreter::String; - std::string path = get_package_share_directory("openscenario_interpreter") + - "/test/parameter_value_distribution/Stochastic.ProbabilityDistributionSet.xosc"; + std::string path = + get_package_share_directory("openscenario_interpreter") + + "/test/parameter_value_distribution/Stochastic.ProbabilityDistributionSet.xosc"; ParameterDistribution expected_distribution; expected_distribution.push_back(makeParameterListSharedPtr("offset", "0.0")); @@ -221,9 +228,12 @@ TEST(ParameterValueDistribution, UniformDistribution) "/test/parameter_value_distribution/Stochastic.UniformDistribution.xosc"; ParameterDistribution expected_distribution; - expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.185689233033365264091685276071)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.688531488513196565648399882775)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.715891239979659754766316837049)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.185689233033365264091685276071)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.688531488513196565648399882775)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.715891239979659754766316837049)); checkParameterValueDistribution(path, expected_distribution); } From bec65148995933006f10cd234a9d8cf4fd43e68f Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 22 Apr 2024 14:19:31 +0900 Subject: [PATCH 100/120] fix: retry derivation if it over the range instead of using std::clamp --- .../src/syntax/log_normal_distribution.cpp | 11 ++++++++++- .../src/syntax/normal_distribution.cpp | 14 +++++++++++++- .../src/syntax/poisson_distribution.cpp | 11 ++++++++++- .../src/syntax/uniform_distribution.cpp | 14 +++++++++++++- 4 files changed, 46 insertions(+), 4 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp index 071ecb50e30..891e72e1867 100644 --- a/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/log_normal_distribution.cpp @@ -33,7 +33,16 @@ LogNormalDistribution::LogNormalDistribution( auto LogNormalDistribution::derive() -> Object { - return make(range.evaluate(distribute(random_engine))); + return make([&]() { + double value; + auto in_range = [this](double value) { + return range.lower_limit.data <= value and value <= range.upper_limit.data; + }; + do { + value = distribute(random_engine); + } while (not in_range(value)); + return value; + }()); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp index 56deadfdbf5..cb8c404de0b 100644 --- a/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/normal_distribution.cpp @@ -31,6 +31,18 @@ NormalDistribution::NormalDistribution( { } -auto NormalDistribution::derive() -> Object { return make(distribute(random_engine)); } +auto NormalDistribution::derive() -> Object +{ + return make([&]() { + double value; + auto in_range = [this](double value) { + return range.lower_limit.data <= value and value <= range.upper_limit.data; + }; + do { + value = distribute(random_engine); + } while (not in_range(value)); + return value; + }()); +} } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp index c28dc271046..ba62599d0fc 100644 --- a/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/poisson_distribution.cpp @@ -30,7 +30,16 @@ PoissonDistribution::PoissonDistribution( auto PoissonDistribution::derive() -> Object { - return make(range.evaluate(distribute(random_engine))); + return make([&]() { + double value; + auto in_range = [this](double value) { + return range.lower_limit.data <= value and value <= range.upper_limit.data; + }; + do { + value = distribute(random_engine); + } while (not in_range(value)); + return value; + }()); } } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp index 223be5f217e..c38379a76b8 100644 --- a/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/uniform_distribution.cpp @@ -27,6 +27,18 @@ UniformDistribution::UniformDistribution( { } -auto UniformDistribution::derive() -> Object { return make(distribute(random_engine)); } +auto UniformDistribution::derive() -> Object +{ + return make([&]() { + double value; + auto in_range = [this](double value) { + return range.lower_limit.data <= value and value <= range.upper_limit.data; + }; + do { + value = distribute(random_engine); + } while (not in_range(value)); + return value; + }()); +} } // namespace syntax } // namespace openscenario_interpreter From da24b36a5512ba963fe4780b1d459f84ddcccd53 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 22 Apr 2024 14:20:49 +0900 Subject: [PATCH 101/120] refactor: use std::default_random_engine for parameter value distribution --- .../include/openscenario_interpreter/scope.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/scope.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/scope.hpp index d8a8f844681..d26dfc1726d 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/scope.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/scope.hpp @@ -194,7 +194,7 @@ class Scope std::list actors; // NOTE: `random_engine` is used only for sharing random number generator in Stochastic now - std::mt19937 random_engine; + std::default_random_engine random_engine; Scope() = delete; From 44a470d7fc0b50365101d52692f27de26d73aca9 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 22 Apr 2024 15:12:49 +0900 Subject: [PATCH 102/120] refactor: update test parameters --- .../test_parameter_value_distribution.cpp | 115 +++--------------- 1 file changed, 19 insertions(+), 96 deletions(-) diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp index 2dd886238eb..bb02e2b47e9 100644 --- a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -137,11 +137,11 @@ TEST(ParameterValueDistribution, Histogram) ParameterDistribution expected_distribution; expected_distribution.push_back( - makeParameterListSharedPtr("offset", -0.657155383483317367954157361964)); + makeParameterListSharedPtr("offset", -1.000000000000000000000000000000)); expected_distribution.push_back( - makeParameterListSharedPtr("offset", -0.122937022973606868703200234449)); + makeParameterListSharedPtr("offset", -0.791349867976780196876518402860)); expected_distribution.push_back( - makeParameterListSharedPtr("offset", -0.068217520040680490467366325902)); + makeParameterListSharedPtr("offset", -1.000000000000000000000000000000)); checkParameterValueDistribution(path, expected_distribution); } @@ -155,9 +155,12 @@ TEST(ParameterValueDistribution, LogNormalDistribution) "/test/parameter_value_distribution/Stochastic.LogNormalDistribution.xosc"; ParameterDistribution expected_distribution; - expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.0)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.0)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.0)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.679981508546370405632330857770)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.032166799749118187012886238563)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.033371713868564217841949925969)); checkParameterValueDistribution(path, expected_distribution); } @@ -172,11 +175,11 @@ TEST(ParameterValueDistribution, NormalDistribution) ParameterDistribution expected_distribution; expected_distribution.push_back( - makeParameterListSharedPtr("offset", 0.793935916513793027426970638771)); + makeParameterListSharedPtr("offset", -0.086242833039257865701543437353)); expected_distribution.push_back( - makeParameterListSharedPtr("offset", 0.214115627062221924870044631461)); + makeParameterListSharedPtr("offset", -0.768496409013107117935703627154)); expected_distribution.push_back( - makeParameterListSharedPtr("offset", 0.050105047474801357731966078290)); + makeParameterListSharedPtr("offset", 0.483866059556305461164527059736)); checkParameterValueDistribution(path, expected_distribution); } @@ -194,8 +197,8 @@ TEST(ParameterValueDistribution, PoissonDistribution) ParameterDistribution expected_distribution; expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.0)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", 1.0)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", 1.0)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.0)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.0)); checkParameterValueDistribution(path, expected_distribution); } @@ -211,9 +214,9 @@ TEST(ParameterValueDistribution, ProbabilityDistributionSet) "/test/parameter_value_distribution/Stochastic.ProbabilityDistributionSet.xosc"; ParameterDistribution expected_distribution; + expected_distribution.push_back(makeParameterListSharedPtr("offset", "-1.0")); expected_distribution.push_back(makeParameterListSharedPtr("offset", "0.0")); - expected_distribution.push_back(makeParameterListSharedPtr("offset", "1.0")); - expected_distribution.push_back(makeParameterListSharedPtr("offset", "1.0")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "-1.0")); checkParameterValueDistribution(path, expected_distribution); } @@ -229,95 +232,15 @@ TEST(ParameterValueDistribution, UniformDistribution) ParameterDistribution expected_distribution; expected_distribution.push_back( - makeParameterListSharedPtr("offset", 0.185689233033365264091685276071)); + makeParameterListSharedPtr("offset", -0.736924424522478638266420603031)); expected_distribution.push_back( - makeParameterListSharedPtr("offset", 0.688531488513196565648399882775)); + makeParameterListSharedPtr("offset", -0.082699735953560393753036805720)); expected_distribution.push_back( - makeParameterListSharedPtr("offset", 0.715891239979659754766316837049)); + makeParameterListSharedPtr("offset", -0.562081627575042097610946711939)); checkParameterValueDistribution(path, expected_distribution); } -// -// TEST(Error, Success) -// { -// using ament_index_cpp::get_package_share_directory; -// -// auto node { -// std::make_shared("", rclcpp::NodeOptions()) -// }; -// -// openscenario_interpreter::OpenScenario evaluate { -// get_package_share_directory("openscenario_interpreter") + "/test/success.xosc", -// node -// }; -// -// ASSERT_FALSE(evaluate.complete()); -// -// const auto begin {std::chrono::high_resolution_clock::now()}; -// -// using std::chrono_literals::operator""ms; -// -// rclcpp::WallRate rate {50ms}; -// -// using openscenario_interpreter::complete_state; -// -// for (evaluate.init(); evaluate() != complete_state; rate.sleep()) { -// ASSERT_LT( -// std::chrono::duration_cast( -// std::chrono::high_resolution_clock::now() - begin).count(), -// 20); -// } -// } - -// TEST(Syntax, invalid) -// { -// auto f = []() -// { -// openscenario_interpreter::OpenSCENARIO osc { XOSC("invalid-1.xosc") }; -// }; -// -// EXPECT_THROW({ f(); }, openscenario_interpreter::SyntaxError); -// } - -// TEST(Syntax, scenarioDefinition) -// { -// using namespace openscenario_interpreter; -// -// OpenSCENARIO osc { XOSC("example.xosc"), "127.0.0.1", 5555 }; -// -// // EXPECT_TRUE(osc.element("FileHeader")); -// // EXPECT_TRUE(osc.element("ParameterDeclarations")); -// -// // EXPECT_EQ(osc["FileHeader"].revMajor(), 1); -// // EXPECT_TRUE(osc.catalog_locations); -// // EXPECT_TRUE(osc.entities); -// // EXPECT_TRUE(osc.parameter_declarations); -// // EXPECT_TRUE(osc.road_network); -// // EXPECT_TRUE(osc.storyboard); -// -// EXPECT_TRUE(osc.evaluate().is()); -// } - -// TEST(Core, objectBinder) -// { -// using openscenario_interpreter::make; -// -// const auto foo {make(3.14)}; -// -// const auto result {foo.evaluate()}; -// -// EXPECT_TRUE(result.is()); -// EXPECT_TRUE(result.as().data = 3.14); -// } - -// TEST(Scenario, LaneChange) -// { -// using namespace openscenario_interpreter; -// -// OpenSCENARIO osc { XOSC("lane_change.xosc"), "127.0.0.1", 5555 }; -// } - int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); From d28bc1dd91d99b04b78f72ff5ca45261fb129873 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 23 Apr 2024 15:26:24 +0900 Subject: [PATCH 103/120] refactor: rename ParameterList into ParameterSet --- .../parameter_distribution.hpp | 14 ++++++++------ .../src/parameter_distribution.cpp | 12 ++++++------ ...deterministic_single_parameter_distribution.cpp | 2 +- .../src/syntax/stochastic.cpp | 6 +++--- .../test/test_parameter_value_distribution.cpp | 14 +++++++------- 5 files changed, 25 insertions(+), 23 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp index 3f501404873..ad3a4e4fcab 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -24,17 +24,19 @@ namespace openscenario_interpreter { -// data container types of distribution -using ParameterList = std::unordered_map; -using ParameterListSharedPtr = std::shared_ptr; -using ParameterDistribution = std::vector; +// parameter set like {a: 1.0, b: 2.0,...} +using ParameterSet = std::unordered_map; +using ParameterSetSharedPtr = std::shared_ptr; +// list of ParameterList +using ParameterDistribution = std::vector; using SingleUnnamedParameterDistribution = std::vector; -struct ParallelDerivableParameterDistributionBase +// TODO(HansRobo): implement parallel derivable parameter distribution with this base struct +struct ParallelDerivableParameterValueDistributionBase { virtual auto derive( std::size_t local_index, std::size_t local_size, std::size_t global_index, - std::size_t global_size) -> ParameterList = 0; + std::size_t global_size) -> ParameterSet = 0; virtual auto getNumberOfDeriveScenarios() const -> std::size_t { diff --git a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp index d5d763ece69..cd8ad2166ea 100644 --- a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp @@ -21,16 +21,16 @@ auto mergeParameterDistribution( -> ParameterDistribution { if (distribution.empty()) { - distribution.emplace_back(std::make_shared()); + distribution.emplace_back(std::make_shared()); } ParameterDistribution merged_distribution; merged_distribution.reserve(distribution.size() * additional_distribution.size()); - for (const ParameterListSharedPtr additional_parameter_list : additional_distribution) { - for (const ParameterListSharedPtr list : distribution) { - auto merged_list = ParameterList{*list}; - merged_list.insert(additional_parameter_list->cbegin(), additional_parameter_list->cend()); - merged_distribution.emplace_back(std::make_shared(merged_list)); + for (const ParameterSetSharedPtr additional_parameter_set : additional_distribution) { + for (const ParameterSetSharedPtr parameter_set : distribution) { + auto merged_set = ParameterSet{*parameter_set}; + merged_set.insert(additional_parameter_set->cbegin(), additional_parameter_set->cend()); + merged_distribution.emplace_back(std::make_shared(merged_set)); } } return merged_distribution; diff --git a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp index 4c79c3d7a76..af24c36f697 100644 --- a/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/deterministic_single_parameter_distribution.cpp @@ -34,7 +34,7 @@ auto DeterministicSingleParameterDistribution::derive() -> ParameterDistribution ParameterDistribution distribution; for (const auto & unnamed_parameter : unnamed_distribution.derive()) { distribution.emplace_back( - std::make_shared(ParameterList{{parameter_name, unnamed_parameter}})); + std::make_shared(ParameterSet{{parameter_name, unnamed_parameter}})); } return distribution; }, diff --git a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp index a428814268d..cf1978ada73 100644 --- a/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/stochastic.cpp @@ -41,12 +41,12 @@ auto Stochastic::derive() -> ParameterDistribution { ParameterDistribution distribution; for (std::size_t i = 0; i < number_of_test_runs; i++) { - ParameterListSharedPtr parameter_list = std::make_shared(); + ParameterSetSharedPtr parameter_set = std::make_shared(); for (auto & stochastic_distribution : stochastic_distributions) { auto derived = stochastic_distribution.derive(); - parameter_list->emplace(stochastic_distribution.parameter_name, derived); + parameter_set->emplace(stochastic_distribution.parameter_name, derived); } - distribution.emplace_back(parameter_list); + distribution.emplace_back(parameter_set); } return distribution; } diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp index bb02e2b47e9..8786904b91f 100644 --- a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -71,9 +71,9 @@ void checkParameterValueDistribution(const std::string path, const ParameterDist template auto makeParameterListSharedPtr(const std::string & name, U value) { - auto parameter_list = std::make_shared(); - (*parameter_list)[name] = openscenario_interpreter::make(value); - return parameter_list; + auto parameter_set = std::make_shared(); + (*parameter_set)[name] = openscenario_interpreter::make(value); + return parameter_set; } TEST(ParameterValueDistribution, DistributionRange) @@ -118,10 +118,10 @@ TEST(ParameterValueDistribution, ValueSetDistribution) "/test/parameter_value_distribution/Deterministic.ValueSetDistribution.xosc"; ParameterDistribution expected_distribution; - auto parameter_list = std::make_shared(); - (*parameter_list)["LANE_ID"] = make("34564"); - (*parameter_list)["offset"] = make("1.0"); - expected_distribution.push_back(parameter_list); + auto parameter_set = std::make_shared(); + (*parameter_set)["LANE_ID"] = make("34564"); + (*parameter_set)["offset"] = make("1.0"); + expected_distribution.push_back(parameter_set); checkParameterValueDistribution(path, expected_distribution); } From 872212f98b2c1a43fcb3703913c7ffe18c2315d2 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 24 Apr 2024 14:36:27 +0900 Subject: [PATCH 104/120] fix: cmake configuration for openscenario_validator --- openscenario/openscenario_validator/CMakeLists.txt | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/openscenario/openscenario_validator/CMakeLists.txt b/openscenario/openscenario_validator/CMakeLists.txt index bf7aeea72f7..79013104533 100644 --- a/openscenario/openscenario_validator/CMakeLists.txt +++ b/openscenario/openscenario_validator/CMakeLists.txt @@ -9,11 +9,10 @@ file(READ ${CMAKE_CURRENT_SOURCE_DIR}/configure/OpenSCENARIO-1.3.xsd ${PROJECT_N configure_file(configure/schema.cpp src/schema.cpp) -include_directories(${XercesC_INCLUDE_DIRS} include) - add_library(${PROJECT_NAME} STATIC src/schema.cpp) target_link_libraries(${PROJECT_NAME} ${XercesC_LIBRARIES}) +target_include_directories(${PROJECT_NAME} PUBLIC ${XercesC_INCLUDE_DIRS} include) add_executable(validate src/validator_command.cpp) @@ -21,7 +20,10 @@ add_executable(validate target_link_libraries(validate ${PROJECT_NAME}) install(TARGETS ${PROJECT_NAME} - INCLUDES DESTINATION include/${PROJECT_NAME}) + DESTINATION lib/${PROJECT_NAME}) + +install(DIRECTORY include/ + DESTINATION include) install(TARGETS validate DESTINATION lib/${PROJECT_NAME}) From 988292611d15ddd996f1ba9e13a21c0f2cdfcee2 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 24 Apr 2024 14:37:35 +0900 Subject: [PATCH 105/120] refactor: stop using nifty counter in OpenSCENARIOValidator --- .../openscenario_validator/validator.hpp | 53 +++++++------------ 1 file changed, 18 insertions(+), 35 deletions(-) diff --git a/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp b/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp index a4d51e492eb..57f2f57b162 100644 --- a/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp +++ b/openscenario/openscenario_validator/include/openscenario_validator/validator.hpp @@ -62,63 +62,46 @@ class OpenSCENARIOValidator } }; - struct XMLPlatform - { - XMLPlatform() - { - if (not count++) { - xercesc::XMLPlatformUtils::Initialize(); - } - } - - ~XMLPlatform() - { - if (not --count) { - xercesc::XMLPlatformUtils::Terminate(); - } - } - int count = 0; - }; - - static void initializeXMLPlatform() - { - // initialize XML platform once by singleton pattern - static XMLPlatform platform; - } - - xercesc::XercesDOMParser parser; + std::unique_ptr parser; ErrorHandler error_handler; static constexpr auto schema_filepath = "/tmp/OpenSCENARIO-1.3.xsd"; public: - explicit OpenSCENARIOValidator() + OpenSCENARIOValidator() { - initializeXMLPlatform(); + xercesc::XMLPlatformUtils::Initialize(); + parser = std::make_unique(); if (auto file = std::ofstream(schema_filepath, std::ios::trunc)) { file << schema; } else { throw std::system_error(errno, std::system_category()); } - if (not parser.loadGrammar(schema_filepath, xercesc::Grammar::SchemaGrammarType)) { + if (not parser->loadGrammar(schema_filepath, xercesc::Grammar::SchemaGrammarType)) { throw std::runtime_error( "Failed to load XSD schema. This is an unexpected error and an implementation issue. " "Please contact the developer."); } else { - parser.setDoNamespaces(true); - parser.setDoSchema(true); - parser.setErrorHandler(&error_handler); - parser.setExternalNoNamespaceSchemaLocation(schema_filepath); - parser.setValidationSchemaFullChecking(true); - parser.setValidationScheme(xercesc::XercesDOMParser::Val_Always); + parser->setDoNamespaces(true); + parser->setDoSchema(true); + parser->setErrorHandler(&error_handler); + parser->setExternalNoNamespaceSchemaLocation(schema_filepath); + parser->setValidationSchemaFullChecking(true); + parser->setValidationScheme(xercesc::XercesDOMParser::Val_Always); } } + ~OpenSCENARIOValidator() + { + parser.release(); + xercesc::XMLPlatformUtils::Terminate(); + } + auto validate(const boost::filesystem::path & xml_file) -> void { - parser.parse(xml_file.string().c_str()); + parser->parse(xml_file.string().c_str()); } template From f8df5895f8cc820a2c86a0797bff3477c48e73a2 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 24 Apr 2024 14:38:47 +0900 Subject: [PATCH 106/120] chore: update test for ProbabilityDistributionSet --- .../Deterministic.DistributionRange.xosc | 4 ++-- .../test/test_parameter_value_distribution.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.DistributionRange.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.DistributionRange.xosc index 4463e25a4ac..33d6ea35699 100644 --- a/openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.DistributionRange.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.DistributionRange.xosc @@ -1,11 +1,11 @@ - + - + diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp index 8786904b91f..321ac2bd4be 100644 --- a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -215,8 +215,8 @@ TEST(ParameterValueDistribution, ProbabilityDistributionSet) ParameterDistribution expected_distribution; expected_distribution.push_back(makeParameterListSharedPtr("offset", "-1.0")); - expected_distribution.push_back(makeParameterListSharedPtr("offset", "0.0")); - expected_distribution.push_back(makeParameterListSharedPtr("offset", "-1.0")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "-0.47")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "0.59")); checkParameterValueDistribution(path, expected_distribution); } From a2882b6e874a1af9de9482a694229b1d5456bac3 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 25 Apr 2024 09:20:48 +0900 Subject: [PATCH 107/120] fix: adjust export settings of openscenario_validator --- openscenario/openscenario_validator/CMakeLists.txt | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/openscenario/openscenario_validator/CMakeLists.txt b/openscenario/openscenario_validator/CMakeLists.txt index 79013104533..1bf9cbf94e4 100644 --- a/openscenario/openscenario_validator/CMakeLists.txt +++ b/openscenario/openscenario_validator/CMakeLists.txt @@ -12,15 +12,17 @@ configure_file(configure/schema.cpp src/schema.cpp) add_library(${PROJECT_NAME} STATIC src/schema.cpp) target_link_libraries(${PROJECT_NAME} ${XercesC_LIBRARIES}) -target_include_directories(${PROJECT_NAME} PUBLIC ${XercesC_INCLUDE_DIRS} include) +target_include_directories(${PROJECT_NAME} PUBLIC + $ + $) add_executable(validate src/validator_command.cpp) target_link_libraries(validate ${PROJECT_NAME}) -install(TARGETS ${PROJECT_NAME} - DESTINATION lib/${PROJECT_NAME}) +ament_export_include_directories(include) +ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) install(DIRECTORY include/ DESTINATION include) @@ -28,7 +30,8 @@ install(DIRECTORY include/ install(TARGETS validate DESTINATION lib/${PROJECT_NAME}) -ament_export_include_directories(include) -ament_export_libraries(${PROJECT_NAME}) +install(TARGETS ${PROJECT_NAME} + EXPORT export_${PROJECT_NAME} + ARCHIVE DESTINATION lib/${PROJECT_NAME}) ament_package() From 7e1bff96d69d2daf5db9bba1aac425402a4b1297 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 25 Apr 2024 13:20:37 +0900 Subject: [PATCH 108/120] refactor: use const reference in ranged for loop --- .../openscenario_interpreter/src/parameter_distribution.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp index cd8ad2166ea..40f35a2dbf4 100644 --- a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp @@ -26,8 +26,8 @@ auto mergeParameterDistribution( ParameterDistribution merged_distribution; merged_distribution.reserve(distribution.size() * additional_distribution.size()); - for (const ParameterSetSharedPtr additional_parameter_set : additional_distribution) { - for (const ParameterSetSharedPtr parameter_set : distribution) { + for (const ParameterSetSharedPtr & additional_parameter_set : additional_distribution) { + for (const ParameterSetSharedPtr & parameter_set : distribution) { auto merged_set = ParameterSet{*parameter_set}; merged_set.insert(additional_parameter_set->cbegin(), additional_parameter_set->cend()); merged_distribution.emplace_back(std::make_shared(merged_set)); From d15d16b37c2dc6d5a2e5a1f847de68a80a4fdd83 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 25 Apr 2024 14:41:22 +0900 Subject: [PATCH 109/120] refactor: use const reference --- .../include/openscenario_interpreter/parameter_distribution.hpp | 2 +- .../openscenario_interpreter/src/parameter_distribution.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp index ad3a4e4fcab..9b39fda6c27 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/parameter_distribution.hpp @@ -67,7 +67,7 @@ struct ParameterDistributionContainer }; auto mergeParameterDistribution( - ParameterDistribution & distribution, ParameterDistribution && additional_distribution) + const ParameterDistribution & distribution, const ParameterDistribution & additional_distribution) -> ParameterDistribution; template diff --git a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp index 40f35a2dbf4..f10267c413d 100644 --- a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp @@ -17,7 +17,7 @@ namespace openscenario_interpreter { auto mergeParameterDistribution( - ParameterDistribution & distribution, ParameterDistribution && additional_distribution) + const ParameterDistribution & distribution, const ParameterDistribution & additional_distribution) -> ParameterDistribution { if (distribution.empty()) { From 1f51e47e885890a2f101753c70d2b5cdb56bbbd4 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 25 Apr 2024 14:41:39 +0900 Subject: [PATCH 110/120] refactor: mergeParameterDistribution --- .../src/parameter_distribution.cpp | 27 +++++++++++-------- 1 file changed, 16 insertions(+), 11 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp index f10267c413d..30496508288 100644 --- a/openscenario/openscenario_interpreter/src/parameter_distribution.cpp +++ b/openscenario/openscenario_interpreter/src/parameter_distribution.cpp @@ -20,19 +20,24 @@ auto mergeParameterDistribution( const ParameterDistribution & distribution, const ParameterDistribution & additional_distribution) -> ParameterDistribution { - if (distribution.empty()) { - distribution.emplace_back(std::make_shared()); - } - - ParameterDistribution merged_distribution; - merged_distribution.reserve(distribution.size() * additional_distribution.size()); - for (const ParameterSetSharedPtr & additional_parameter_set : additional_distribution) { + if (distribution.empty() and additional_distribution.empty()) { + throw common::Error( + "trying to merge two parameter distributions but failed because both are empty"); + } else if (distribution.empty()) { + return additional_distribution; + } else if (additional_distribution.empty()) { + return distribution; + } else { + ParameterDistribution merged_distribution; + merged_distribution.reserve(distribution.size() * additional_distribution.size()); for (const ParameterSetSharedPtr & parameter_set : distribution) { - auto merged_set = ParameterSet{*parameter_set}; - merged_set.insert(additional_parameter_set->cbegin(), additional_parameter_set->cend()); - merged_distribution.emplace_back(std::make_shared(merged_set)); + for (const ParameterSetSharedPtr & additional_parameter_set : additional_distribution) { + auto merged_set = ParameterSet{*parameter_set}; + merged_set.insert(additional_parameter_set->cbegin(), additional_parameter_set->cend()); + merged_distribution.emplace_back(std::make_shared(merged_set)); + } } + return merged_distribution; } - return merged_distribution; } } // namespace openscenario_interpreter From c12fbf312bd5ab56c3a6984f52ec4e0daf482c12 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 25 Apr 2024 14:42:25 +0900 Subject: [PATCH 111/120] refactor: Improved accuracy of results in DistributionRange --- .../src/syntax/distribution_range.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp index e2c1c5bf8f6..f2309b802c9 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp @@ -29,9 +29,11 @@ DistributionRange::DistributionRange(const pugi::xml_node & node, Scope & scope) auto DistributionRange::derive() -> SingleUnnamedParameterDistribution { SingleUnnamedParameterDistribution unnamed_distribution; - for (double parameter = range.lower_limit; parameter <= range.upper_limit; - parameter += step_width) { - unnamed_distribution.emplace_back(make(parameter)); + const auto number_of_parameters = + static_cast((range.upper_limit - range.lower_limit) / step_width); + for (std::size_t i = 0; i < number_of_parameters; ++i) { + unnamed_distribution.emplace_back( + make(range.lower_limit + static_cast(i) * step_width)); } return unnamed_distribution; } From 7b1b3a480fa2c13e37ce05a72ec7fc4d8907e271 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 25 Apr 2024 14:43:58 +0900 Subject: [PATCH 112/120] feat: add test for merging deterministic distributions --- .../Deterministic.xosc | 20 +++++++++++ .../test_parameter_value_distribution.cpp | 33 +++++++++++++++++++ 2 files changed, 53 insertions(+) create mode 100644 openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.xosc diff --git a/openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.xosc new file mode 100644 index 00000000000..c1811ce047b --- /dev/null +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Deterministic.xosc @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp index 321ac2bd4be..cfb2a7ca1fe 100644 --- a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -126,6 +126,39 @@ TEST(ParameterValueDistribution, ValueSetDistribution) checkParameterValueDistribution(path, expected_distribution); } +TEST(ParameterValueDistribution, Deterministic) +{ + using ament_index_cpp::get_package_share_directory; + using openscenario_interpreter::Double; + using openscenario_interpreter::make; + using openscenario_interpreter::String; + + std::string path = get_package_share_directory("openscenario_interpreter") + + "/test/parameter_value_distribution/Deterministic.xosc"; + + ParameterDistribution expected_distribution; + auto make_parameter_set = [](double offset, std::string lane_id) { + auto parameter_set = std::make_shared(); + (*parameter_set)["offset"] = make(offset); + (*parameter_set)["LANE_ID"] = make(lane_id); + return parameter_set; + }; + expected_distribution.push_back(make_parameter_set(-1.0, "34510")); + expected_distribution.push_back(make_parameter_set(-1.0, "34513")); + expected_distribution.push_back(make_parameter_set(-1.0, "34564")); + expected_distribution.push_back(make_parameter_set(-0.47, "34510")); + expected_distribution.push_back(make_parameter_set(-0.47, "34513")); + expected_distribution.push_back(make_parameter_set(-0.47, "34564")); + expected_distribution.push_back(make_parameter_set(0.06, "34510")); + expected_distribution.push_back(make_parameter_set(0.06, "34513")); + expected_distribution.push_back(make_parameter_set(0.06, "34564")); + expected_distribution.push_back(make_parameter_set(0.59, "34510")); + expected_distribution.push_back(make_parameter_set(0.59, "34513")); + expected_distribution.push_back(make_parameter_set(0.59, "34564")); + + checkParameterValueDistribution(path, expected_distribution); +} + // Histogram TEST(ParameterValueDistribution, Histogram) { From 161cfac5f25cb43d29c3342062096c1eed2ea2ea Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 25 Apr 2024 14:44:26 +0900 Subject: [PATCH 113/120] refactor: use EXPECT_DOUBLE_EQ for testing double variables --- .../test/test_parameter_value_distribution.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp index cfb2a7ca1fe..cb719c8aa30 100644 --- a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -58,7 +58,7 @@ void checkParameterValueDistribution(const std::string path, const ParameterDist } else if (expected_parameter.is()) { EXPECT_EQ(expected_parameter.as(), actual_parameter.as()); } else if (expected_parameter.is()) { - EXPECT_EQ(expected_parameter.as(), actual_parameter.as()); + EXPECT_DOUBLE_EQ(expected_parameter.as(), actual_parameter.as()); } else if (expected_parameter.is()) { EXPECT_EQ(expected_parameter.as(), actual_parameter.as()); } else { From 6e9885b377c2c952632d4e4104104905f95f7320 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 25 Apr 2024 14:45:34 +0900 Subject: [PATCH 114/120] fix: fix modify test value due to random engine update --- .../test/test_parameter_value_distribution.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp index cb719c8aa30..d32e5f35240 100644 --- a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -86,8 +86,9 @@ TEST(ParameterValueDistribution, DistributionRange) ParameterDistribution expected_distribution; expected_distribution.push_back(makeParameterListSharedPtr("offset", -1.0)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.0)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", 1.0)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", -0.47)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.06)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.59)); checkParameterValueDistribution(path, expected_distribution); } @@ -172,7 +173,7 @@ TEST(ParameterValueDistribution, Histogram) expected_distribution.push_back( makeParameterListSharedPtr("offset", -1.000000000000000000000000000000)); expected_distribution.push_back( - makeParameterListSharedPtr("offset", -0.791349867976780196876518402860)); + makeParameterListSharedPtr("offset", -0.845241258489508595630468335003)); expected_distribution.push_back( makeParameterListSharedPtr("offset", -1.000000000000000000000000000000)); From 6aeb6a3e578cc4d6987064a090358f57c9e1bd35 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 25 Apr 2024 14:46:17 +0900 Subject: [PATCH 115/120] chore: improve test for ProbabilityDistributionSet --- ...Stochastic.ProbabilityDistributionSet.xosc | 8 +++--- .../test_parameter_value_distribution.cpp | 28 +++++++++++++++++-- 2 files changed, 29 insertions(+), 7 deletions(-) diff --git a/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.ProbabilityDistributionSet.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.ProbabilityDistributionSet.xosc index 2121fb3922f..aa552b138a6 100644 --- a/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.ProbabilityDistributionSet.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.ProbabilityDistributionSet.xosc @@ -3,12 +3,12 @@ - + - - - + + + diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp index d32e5f35240..4bf18def219 100644 --- a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -248,9 +248,31 @@ TEST(ParameterValueDistribution, ProbabilityDistributionSet) "/test/parameter_value_distribution/Stochastic.ProbabilityDistributionSet.xosc"; ParameterDistribution expected_distribution; - expected_distribution.push_back(makeParameterListSharedPtr("offset", "-1.0")); - expected_distribution.push_back(makeParameterListSharedPtr("offset", "-0.47")); - expected_distribution.push_back(makeParameterListSharedPtr("offset", "0.59")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "1")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "2")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "1")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "2")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "3")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "2")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "1")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "2")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "1")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "1")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "2")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "3")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "2")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "2")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "2")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "3")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "1")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "2")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "3")); + expected_distribution.push_back(makeParameterListSharedPtr("offset", "2")); + + // NOTE: + // 1, ideal: 5/20, actual: 6/20 + // 2: ideal: 10/20, actual: 10/20 + // 3: ideal: 5/20, actual: 4/20 checkParameterValueDistribution(path, expected_distribution); } From 6b0d1a11b47b8e5d2714ed5ee377a9f460f2a0b3 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 25 Apr 2024 15:03:33 +0900 Subject: [PATCH 116/120] refactor: refactor tests --- .../test_parameter_value_distribution.cpp | 56 ++++++++++++------- 1 file changed, 37 insertions(+), 19 deletions(-) diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp index 4bf18def219..7f7a258f893 100644 --- a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -84,11 +84,16 @@ TEST(ParameterValueDistribution, DistributionRange) std::string path = get_package_share_directory("openscenario_interpreter") + "/test/parameter_value_distribution/Deterministic.DistributionRange.xosc"; + double offset0 = -1.0 + 0.53 * 0; // -1.0 + double offset1 = -1.0 + 0.53 * 1; // -0.47 + double offset2 = -1.0 + 0.53 * 2; // 0.06 + double offset3 = -1.0 + 0.53 * 3; // 0.59 + ParameterDistribution expected_distribution; - expected_distribution.push_back(makeParameterListSharedPtr("offset", -1.0)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", -0.47)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.06)); - expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.59)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", offset0)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", offset1)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", offset2)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", offset3)); checkParameterValueDistribution(path, expected_distribution); } @@ -144,18 +149,34 @@ TEST(ParameterValueDistribution, Deterministic) (*parameter_set)["LANE_ID"] = make(lane_id); return parameter_set; }; - expected_distribution.push_back(make_parameter_set(-1.0, "34510")); - expected_distribution.push_back(make_parameter_set(-1.0, "34513")); - expected_distribution.push_back(make_parameter_set(-1.0, "34564")); - expected_distribution.push_back(make_parameter_set(-0.47, "34510")); - expected_distribution.push_back(make_parameter_set(-0.47, "34513")); - expected_distribution.push_back(make_parameter_set(-0.47, "34564")); - expected_distribution.push_back(make_parameter_set(0.06, "34510")); - expected_distribution.push_back(make_parameter_set(0.06, "34513")); - expected_distribution.push_back(make_parameter_set(0.06, "34564")); - expected_distribution.push_back(make_parameter_set(0.59, "34510")); - expected_distribution.push_back(make_parameter_set(0.59, "34513")); - expected_distribution.push_back(make_parameter_set(0.59, "34564")); + double offset0 = -1.0 + 0.53 * 0; // -1.0 + double offset1 = -1.0 + 0.53 * 1; // -0.47 + double offset2 = -1.0 + 0.53 * 2; // 0.06 + double offset3 = -1.0 + 0.53 * 3; // 0.59 + std::string lane_id0 = "34510"; + std::string lane_id1 = "34513"; + std::string lane_id2 = "34564"; + + { + expected_distribution.push_back(make_parameter_set(offset0, lane_id0)); + expected_distribution.push_back(make_parameter_set(offset0, lane_id1)); + expected_distribution.push_back(make_parameter_set(offset0, lane_id2)); + } + { + expected_distribution.push_back(make_parameter_set(offset1, lane_id0)); + expected_distribution.push_back(make_parameter_set(offset1, lane_id1)); + expected_distribution.push_back(make_parameter_set(offset1, lane_id2)); + } + { + expected_distribution.push_back(make_parameter_set(offset2, lane_id0)); + expected_distribution.push_back(make_parameter_set(offset2, lane_id1)); + expected_distribution.push_back(make_parameter_set(offset2, lane_id2)); + } + { + expected_distribution.push_back(make_parameter_set(offset3, lane_id0)); + expected_distribution.push_back(make_parameter_set(offset3, lane_id1)); + expected_distribution.push_back(make_parameter_set(offset3, lane_id2)); + } checkParameterValueDistribution(path, expected_distribution); } @@ -218,7 +239,6 @@ TEST(ParameterValueDistribution, NormalDistribution) checkParameterValueDistribution(path, expected_distribution); } -// PoissonDistribution TEST(ParameterValueDistribution, PoissonDistribution) { using ament_index_cpp::get_package_share_directory; @@ -237,7 +257,6 @@ TEST(ParameterValueDistribution, PoissonDistribution) checkParameterValueDistribution(path, expected_distribution); } -// ProbabilityDistribution TEST(ParameterValueDistribution, ProbabilityDistributionSet) { using ament_index_cpp::get_package_share_directory; @@ -277,7 +296,6 @@ TEST(ParameterValueDistribution, ProbabilityDistributionSet) checkParameterValueDistribution(path, expected_distribution); } -// UniformDistribution TEST(ParameterValueDistribution, UniformDistribution) { using ament_index_cpp::get_package_share_directory; From 2d6dead75f55247d9417eddba00aa548befa1b05 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 25 Apr 2024 15:04:04 +0900 Subject: [PATCH 117/120] fix: fix wrong number of derivations in DistributionRange --- .../openscenario_interpreter/src/syntax/distribution_range.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp index f2309b802c9..90941427dc1 100644 --- a/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/distribution_range.cpp @@ -30,7 +30,7 @@ auto DistributionRange::derive() -> SingleUnnamedParameterDistribution { SingleUnnamedParameterDistribution unnamed_distribution; const auto number_of_parameters = - static_cast((range.upper_limit - range.lower_limit) / step_width); + static_cast((range.upper_limit - range.lower_limit) / step_width + 1); for (std::size_t i = 0; i < number_of_parameters; ++i) { unnamed_distribution.emplace_back( make(range.lower_limit + static_cast(i) * step_width)); From 828bc273af533128e0ffdde3d04bf91c3eae7607 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 17 May 2024 15:17:30 +0900 Subject: [PATCH 118/120] fix: fix bug in Histogram::BinAdaptor --- .../include/openscenario_interpreter/syntax/histogram.hpp | 3 +-- .../test/test_parameter_value_distribution.cpp | 6 +++--- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index 43674227e1d..3932b4d7286 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -50,10 +50,9 @@ struct Histogram : public ComplexType, private Scope, public StochasticParameter { intervals.emplace_back(bins.front().range.lower_limit.data); for (const auto & bin : bins) { - intervals.emplace_back(bin.range.lower_limit.data); + intervals.emplace_back(bin.range.upper_limit.data); densities.emplace_back(bin.weight.data); } - intervals.emplace_back(bins.back().range.upper_limit.data); } std::vector intervals, densities; } bin_adaptor; diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp index 7f7a258f893..e3fcd80c2f5 100644 --- a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -192,11 +192,11 @@ TEST(ParameterValueDistribution, Histogram) ParameterDistribution expected_distribution; expected_distribution.push_back( - makeParameterListSharedPtr("offset", -1.000000000000000000000000000000)); + makeParameterListSharedPtr("offset", -0.73692442452247864)); expected_distribution.push_back( - makeParameterListSharedPtr("offset", -0.845241258489508595630468335003)); + makeParameterListSharedPtr("offset", -0.082699735953560394)); expected_distribution.push_back( - makeParameterListSharedPtr("offset", -1.000000000000000000000000000000)); + makeParameterListSharedPtr("offset", -0.5620816275750421)); checkParameterValueDistribution(path, expected_distribution); } From 9279d4b777b7dda69e5895a670faf4efbdf6726a Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 17 May 2024 15:34:54 +0900 Subject: [PATCH 119/120] refactor: delete Histogram::BinAdaptor --- .../openscenario_interpreter/syntax/histogram.hpp | 13 ------------- .../src/syntax/histogram.cpp | 15 ++++++++++----- 2 files changed, 10 insertions(+), 18 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp index 3932b4d7286..bfc8a60a22b 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/histogram.hpp @@ -44,19 +44,6 @@ struct Histogram : public ComplexType, private Scope, public StochasticParameter */ const std::list bins; - struct BinAdaptor - { - explicit BinAdaptor(const std::list & bins) - { - intervals.emplace_back(bins.front().range.lower_limit.data); - for (const auto & bin : bins) { - intervals.emplace_back(bin.range.upper_limit.data); - densities.emplace_back(bin.weight.data); - } - } - std::vector intervals, densities; - } bin_adaptor; - std::piecewise_constant_distribution distribute; explicit Histogram(const pugi::xml_node &, Scope & scope); diff --git a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp index 95e4281b609..3a65b6c9be9 100644 --- a/openscenario/openscenario_interpreter/src/syntax/histogram.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/histogram.cpp @@ -20,11 +20,16 @@ namespace openscenario_interpreter inline namespace syntax { Histogram::Histogram(const pugi::xml_node & node, openscenario_interpreter::Scope & scope) -: Scope(scope), - bins(readElements("Bin", node, scope)), - bin_adaptor(bins), - distribute( - bin_adaptor.intervals.begin(), bin_adaptor.intervals.end(), bin_adaptor.densities.begin()) +: Scope(scope), bins(readElements("Bin", node, scope)), distribute([this]() { + std::vector intervals, densities; + intervals.emplace_back(bins.front().range.lower_limit.data); + for (const auto & bin : bins) { + intervals.emplace_back(bin.range.upper_limit.data); + densities.emplace_back(bin.weight.data); + } + return std::piecewise_constant_distribution::param_type( + intervals.begin(), intervals.end(), densities.begin()); + }()) { } From b77e3ae88b7b9a14894fd1d00f58b05a850aaaa9 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 17 May 2024 16:12:05 +0900 Subject: [PATCH 120/120] chore: update test for Histogram --- .../Stochastic.Histogram.xosc | 2 +- .../test_parameter_value_distribution.cpp | 36 +++++++++++++++++++ 2 files changed, 37 insertions(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.Histogram.xosc b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.Histogram.xosc index 57546eea330..aba60e51f92 100644 --- a/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.Histogram.xosc +++ b/openscenario/openscenario_interpreter/test/parameter_value_distribution/Stochastic.Histogram.xosc @@ -3,7 +3,7 @@ - + diff --git a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp index e3fcd80c2f5..a499d2b9341 100644 --- a/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp +++ b/openscenario/openscenario_interpreter/test/test_parameter_value_distribution.cpp @@ -197,6 +197,42 @@ TEST(ParameterValueDistribution, Histogram) makeParameterListSharedPtr("offset", -0.082699735953560394)); expected_distribution.push_back( makeParameterListSharedPtr("offset", -0.5620816275750421)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.35772943348137098)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.86938579245347758)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.038832744045494971)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", -0.93085577907030514)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.059400386282114415)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", -0.98460362787680167)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", -0.8663155254748649)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.3735454248180905)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.86087298993938566)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.053857555519812195)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.3078379243610454)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.40238118899835329)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", 0.52439607999726823)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", -0.90507097322737606)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", -0.34353154767998462)); + expected_distribution.push_back(makeParameterListSharedPtr("offset", 0.5128209722651722)); + expected_distribution.push_back( + makeParameterListSharedPtr("offset", -0.26932265821684642)); + + // NOTE: + // 1, range: -1.0 ~ -0.5, ideal: 5/20, actual: 6/20 + // 2: range: -0.5 ~ 0.5, ideal: 10/20, actual: 10/20 + // 3: range: 0.5 ~ 1.0, ideal: 5/20, actual: 4/20 checkParameterValueDistribution(path, expected_distribution); }