Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

refactors and small fixes for ParameterValueDistribution-related codes (stochastic) #1510

Draft
wants to merge 21 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
21 commits
Select commit Hold shift + click to select a range
2410614
refactor: store random_engine instead of seed in Scope class
HansRobo Jan 21, 2025
1446393
chore: use Scope::random_engine in stochastic distribution classes
HansRobo Jan 21, 2025
9c3cb80
chore: format
HansRobo Jan 21, 2025
8133d6e
fix: correct name cases to match xsd definition
HansRobo Jan 21, 2025
d12c0c7
refactor: delete Histogram::bin_adaptor
HansRobo Jan 21, 2025
e9788f7
refactor: delete ProbabilityDistributionSet::adaptor
HansRobo Jan 21, 2025
66853af
chore: delete comment-outed code
HansRobo Jan 21, 2025
4ca4ff5
chore: use std::size_t
HansRobo Jan 21, 2025
7e6ae02
refactor: delete helper function for initialization of ProbabilityDis…
HansRobo Jan 21, 2025
04cb6db
refactor: introduce StochasticParameterDistributionBase class
HansRobo Jan 21, 2025
36dde2a
chore: prepare default implementation of StochasticParameterDistribut…
HansRobo Jan 23, 2025
4161787
Merge branch 'master' into parameter_value_distribution_1
HansRobo Jan 27, 2025
3d099a8
Merge branch 'master' into parameter_value_distribution_1
HansRobo Jan 28, 2025
cf2ddd9
Merge branch 'master' into parameter_value_distribution_1
HansRobo Feb 6, 2025
700c23e
Merge branch 'master' into parameter_value_distribution_1
HansRobo Feb 7, 2025
20eb4c8
Merge remote-tracking branch 'origin/parameter_value_distribution_1' …
HansRobo Feb 10, 2025
3db58c4
Merge branch 'master' into parameter_value_distribution_1
HansRobo Feb 14, 2025
4f6db94
Merge branch 'master' into parameter_value_distribution_1
HansRobo Feb 19, 2025
0532520
Merge branch 'master' into parameter_value_distribution_1
HansRobo Feb 27, 2025
a3fae59
Revert "chore: delete comment-outed code"
HansRobo Feb 27, 2025
88ea4f2
chore: revert validator.hpp changes
HansRobo Feb 27, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
// 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 <openscenario_interpreter/object.hpp>

namespace openscenario_interpreter
{
struct StochasticParameterDistributionBase
{
virtual auto derive() -> Object
{
throw common::scenario_simulator_exception::Error(
"Unimplemented derive function is called. Please implement and override "
"StochasticParameterDistributionBase::derive.");
}
};
} // namespace openscenario_interpreter
#endif // OPENSCENARIO_INTERPRETER__PARAMETER_DISTRIBUTION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <openscenario_interpreter/syntax/catalog_locations.hpp>
#include <openscenario_interpreter/syntax/entity.hpp>
#include <openscenario_interpreter/utility/demangle.hpp>
#include <random>
#include <unordered_map>
#include <utility>
#include <vector>
Expand Down Expand Up @@ -192,7 +193,8 @@ class Scope

std::list<Entity> 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::default_random_engine random_engine;

Scope() = delete;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__HISTOGRAM_HPP_
#define OPENSCENARIO_INTERPRETER__SYNTAX__HISTOGRAM_HPP_

#include <openscenario_interpreter/parameter_distribution.hpp>
#include <openscenario_interpreter/scope.hpp>
#include <openscenario_interpreter/syntax/histogram_bin.hpp>
#include <random>
Expand All @@ -34,34 +35,18 @@ inline namespace syntax
</xsd:sequence>
</xsd:complexType>
*/
struct Histogram : public ComplexType, private Scope
struct Histogram : public ComplexType, private Scope, public StochasticParameterDistributionBase
{
/**
* Note: HistogramBin must be stored in continuous range and ascending order, to `bins`
*/
const std::list<HistogramBin> bins;

struct BinAdaptor
{
explicit BinAdaptor(const std::list<HistogramBin> & bins)
{
intervals.emplace_back(bins.front().range.lower_limit.data);
for (const auto & bin : bins) {
intervals.emplace_back(bin.range.lower_limit.data);
densities.emplace_back(bin.weight.data);
}
intervals.emplace_back(bins.back().range.upper_limit.data);
}
std::vector<double> intervals, densities;
} bin_adaptor;

std::piecewise_constant_distribution<Double::value_type> distribute;

std::mt19937 random_engine;

explicit Histogram(const pugi::xml_node &, Scope & scope);

auto evaluate() -> Object;
auto derive() -> Object override;
};
} // namespace syntax
} // namespace openscenario_interpreter
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__NORMAL_DISTRIBUTION_HPP_
#define OPENSCENARIO_INTERPRETER__SYNTAX__NORMAL_DISTRIBUTION_HPP_

#include <openscenario_interpreter/parameter_distribution.hpp>
#include <openscenario_interpreter/scope.hpp>
#include <openscenario_interpreter/syntax/double.hpp>
#include <openscenario_interpreter/syntax/range.hpp>
Expand All @@ -38,7 +39,9 @@ inline namespace syntax
<xsd:attribute name="variance" type="Double" use="required"/>
</xsd:complexType>
*/
struct NormalDistribution : public ComplexType, private Scope
struct NormalDistribution : public ComplexType,
private Scope,
public StochasticParameterDistributionBase
{
const Range range;

Expand All @@ -48,11 +51,9 @@ struct NormalDistribution : public ComplexType, private Scope

std::normal_distribution<Double::value_type> distribute;

std::mt19937 random_engine;

explicit NormalDistribution(const pugi::xml_node &, Scope & scope);

auto evaluate() -> Object;
auto derive() -> Object override;
};
} // namespace syntax
} // namespace openscenario_interpreter
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ struct ParameterAssignment
}

const std::string parameterRef;

const std::string value;
};
} // namespace syntax
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__POISSON_DISTRIBUTION_HPP_
#define OPENSCENARIO_INTERPRETER__SYNTAX__POISSON_DISTRIBUTION_HPP_

#include <openscenario_interpreter/parameter_distribution.hpp>
#include <openscenario_interpreter/scope.hpp>
#include <openscenario_interpreter/syntax/double.hpp>
#include <openscenario_interpreter/syntax/range.hpp>
Expand All @@ -36,19 +37,19 @@ inline namespace syntax
<xsd:attribute name="expectedValue" type="Double" use="required"/>
</xsd:complexType>
*/
struct PoissonDistribution : public ComplexType, private Scope
struct PoissonDistribution : public ComplexType,
private Scope,
public StochasticParameterDistributionBase
{
const Range range;

const Double expected_value;

std::poisson_distribution<> distribute;

std::mt19937 random_engine;

explicit PoissonDistribution(const pugi::xml_node &, Scope & scope);

auto evaluate() -> Object;
auto derive() -> Object override;
};
} // namespace syntax
} // namespace openscenario_interpreter
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__PROBABILITY_DISTRIBUTION_SET_HPP_
#define OPENSCENARIO_INTERPRETER__SYNTAX__PROBABILITY_DISTRIBUTION_SET_HPP_

#include <openscenario_interpreter/parameter_distribution.hpp>
#include <openscenario_interpreter/syntax/probability_distribution_set_element.hpp>
#include <random>

Expand All @@ -33,31 +34,17 @@ inline namespace syntax
</xsd:sequence>
</xsd:complexType>
*/
struct ProbabilityDistributionSet : public ComplexType, private Scope
struct ProbabilityDistributionSet : public ComplexType,
private Scope,
public StochasticParameterDistributionBase
{
const std::vector<ProbabilityDistributionSetElement> elements;

struct ProbabilityDistributionSetAdaptor
{
explicit ProbabilityDistributionSetAdaptor(
const std::vector<ProbabilityDistributionSetElement> & elements)
{
for (const auto & element : elements) {
probabilities.emplace_back(element.weight);
values.emplace_back(element.value);
}
}
std::vector<double> probabilities;
std::vector<String> values;
} adaptor;

std::discrete_distribution<std::size_t> distribute;

std::mt19937 random_engine;

explicit ProbabilityDistributionSet(const pugi::xml_node &, Scope & scope);

auto evaluate() -> Object;
auto derive() -> Object override;
};
} // namespace syntax
} // namespace openscenario_interpreter
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__UNIFORM_DISTRIBUTION_HPP_
#define OPENSCENARIO_INTERPRETER__SYNTAX__UNIFORM_DISTRIBUTION_HPP_

#include <openscenario_interpreter/parameter_distribution.hpp>
#include <openscenario_interpreter/scope.hpp>
#include <openscenario_interpreter/syntax/range.hpp>
#include <random>
Expand All @@ -34,17 +35,17 @@ inline namespace syntax
</xsd:sequence>
</xsd:complexType>
*/
struct UniformDistribution : public ComplexType, private Scope
struct UniformDistribution : public ComplexType,
private Scope,
public StochasticParameterDistributionBase
{
const Range range;

std::uniform_real_distribution<Double::value_type> distribute;

std::mt19937 random_engine;

explicit UniformDistribution(const pugi::xml_node &, Scope & scope);

auto evaluate() -> Object;
auto derive() -> Object override;
};
} // namespace syntax
} // namespace openscenario_interpreter
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<Deterministic>(node,scope);}),
std::make_pair("Stochastic", [&](auto && node){return make<Stochastic >(node,scope);})))
std::make_pair("Deterministic", [&](auto && node){return make<Deterministic>(node,scope);}),
std::make_pair("Stochastic", [&](auto && node){return make<Stochastic >(node,scope);})))
// clang-format on
{
}
Expand Down
18 changes: 11 additions & 7 deletions openscenario/openscenario_interpreter/src/syntax/histogram.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,15 +20,19 @@ namespace openscenario_interpreter
inline namespace syntax
{
Histogram::Histogram(const pugi::xml_node & node, openscenario_interpreter::Scope & scope)
: Scope(scope),
bins(readElements<HistogramBin, 1>("Bin", node, scope)),
bin_adaptor(bins),
distribute(
bin_adaptor.intervals.begin(), bin_adaptor.intervals.end(), bin_adaptor.densities.begin()),
random_engine(scope.seed)
: Scope(scope), bins(readElements<HistogramBin, 1>("Bin", node, scope)), distribute([this]() {
std::vector<double> 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<Double::value_type>::param_type(
intervals.begin(), intervals.end(), densities.begin());
}())
{
}

auto Histogram::evaluate() -> Object { return make<Double>(distribute(random_engine)); }
auto Histogram::derive() -> Object { return make<Double>(distribute(random_engine)); }
} // namespace syntax
} // namespace openscenario_interpreter
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ namespace openscenario_interpreter
inline namespace syntax
{
HistogramBin::HistogramBin(const pugi::xml_node & node, openscenario_interpreter::Scope & scope)
: range(readElement<Range>("range", node, scope)),
: range(readElement<Range>("Range", node, scope)),
weight(readAttribute<Double>("weight", node, scope))
{
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,14 +22,13 @@ inline namespace syntax
NormalDistribution::NormalDistribution(
const pugi::xml_node & node, openscenario_interpreter::Scope & scope)
: Scope(scope),
range(readElement<Range>("range", node, scope)),
range(readElement<Range>("Range", node, scope)),
expected_value(readAttribute<Double>("expectedValue", node, scope)),
variance(readAttribute<Double>("variance", node, scope)),
distribute(static_cast<double>(expected_value.data), static_cast<double>(variance.data)),
random_engine(scope.seed)
distribute(static_cast<double>(expected_value.data), static_cast<double>(variance.data))
{
}

auto NormalDistribution::evaluate() -> Object { return make<Double>(distribute(random_engine)); }
auto NormalDistribution::derive() -> Object { return make<Double>(distribute(random_engine)); }
} // namespace syntax
} // namespace openscenario_interpreter
Original file line number Diff line number Diff line change
Expand Up @@ -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<ScenarioDefinition >(tree, scope);}), // DIRTY HACK!!!
std::make_pair("Catalog", [&](auto && ) { return make<CatalogDefinition >(tree, scope);}),
std::make_pair("ParameterValueDistribution",[&](auto && node) { return make<ParameterValueDistributionDefinition>(node, scope);})))
std::make_pair("Storyboard", [&](auto && ) { return make<ScenarioDefinition >(tree, scope);}), // DIRTY HACK!!!
std::make_pair("Catalog", [&](auto && ) { return make<CatalogDefinition >(tree, scope);}),
std::make_pair("ParameterValueDistribution",[&](auto && node) { return make<ParameterValueDistributionDefinition>(node, scope);})))
// clang-format on
{
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ inline namespace syntax
ParameterValueDistributionDefinition::ParameterValueDistributionDefinition(
const pugi::xml_node & node, Scope & scope)
: ParameterValueDistribution(
readElement<ParameterValueDistribution>("parameterValueDistribution", node, scope))
readElement<ParameterValueDistribution>("ParameterValueDistribution", node, scope))
{
}
} // namespace syntax
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,12 @@ inline namespace syntax
PoissonDistribution::PoissonDistribution(
const pugi::xml_node & node, openscenario_interpreter::Scope & scope)
: Scope(scope),
range(readElement<Range>("range", node, scope)),
range(readElement<Range>("Range", node, scope)),
expected_value(readAttribute<Double>("expectedValue", node, scope)),
distribute(expected_value.data),
random_engine(scope.seed)
distribute(expected_value.data)
{
}

auto PoissonDistribution::evaluate() -> Object { return make<Double>(distribute(random_engine)); }
auto PoissonDistribution::derive() -> Object { return make<Double>(distribute(random_engine)); }
} // namespace syntax
} // namespace openscenario_interpreter
Original file line number Diff line number Diff line change
Expand Up @@ -19,27 +19,25 @@ namespace openscenario_interpreter
{
inline namespace syntax
{
// DIRTY HACK?
template <typename T>
auto generateVector(const std::list<T> & list) -> std::vector<T>
{
return std::vector<T>(list.begin(), list.end());
}

ProbabilityDistributionSet::ProbabilityDistributionSet(
const pugi::xml_node & node, openscenario_interpreter::Scope & scope)
: Scope(scope),
elements(
generateVector(readElements<ProbabilityDistributionSetElement, 1>("Element", node, scope))),
adaptor(elements),
distribute(adaptor.probabilities.begin(), adaptor.probabilities.end()),
random_engine(scope.seed)
elements([](const std::list<ProbabilityDistributionSetElement> & element_list) {
return std::vector<ProbabilityDistributionSetElement>(element_list.begin(), element_list.end());
}(readElements<ProbabilityDistributionSetElement, 1>("Element", node, scope))),
distribute([this]() -> std::discrete_distribution<std::size_t> {
std::vector<double> probabilities;
for (const auto & element : elements) {
probabilities.push_back(element.weight);
}
return {std::begin(probabilities), std::end(probabilities)};
}())
{
}

auto ProbabilityDistributionSet::evaluate() -> Object
auto ProbabilityDistributionSet::derive() -> Object
{
size_t index = distribute(random_engine);
std::size_t index = distribute(random_engine);
return elements.at(index);
}
} // namespace syntax
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,11 @@ inline namespace syntax
*/
Stochastic::Stochastic(const pugi::xml_node & node, Scope & scope)
: number_of_test_runs(readAttribute<UnsignedInt>("numberOfTestRuns", node, scope)),
random_seed(
scope.seed = static_cast<double>(readAttribute<Double>("randomSeed", node, scope, 0))),
random_seed([&] {
auto seed = static_cast<double>(readAttribute<Double>("randomSeed", node, scope, 0));
scope.random_engine.seed(seed);
return seed;
}()),
stochastic_distribution(
readElement<StochasticDistribution>("StochasticDistribution", node, scope))
{
Expand Down
Loading
Loading