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

schema: Rename gaussian std to stddev #13948

Merged
merged 1 commit into from
Aug 27, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
36 changes: 18 additions & 18 deletions common/schema/dev/stochastic.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,13 +46,13 @@ Expression Deterministic::ToSymbolic() const {

Gaussian::Gaussian() {}

Gaussian::Gaussian(double mean_in, double std_in)
: mean(mean_in), std(std_in) {}
Gaussian::Gaussian(double mean_in, double stddev_in)
: mean(mean_in), stddev(stddev_in) {}

Gaussian::~Gaussian() {}

double Gaussian::Sample(drake::RandomGenerator* generator) const {
std::normal_distribution<double> distribution(mean, std);
std::normal_distribution<double> distribution(mean, stddev);
return distribution(*generator);
}

Expand All @@ -61,7 +61,7 @@ double Gaussian::Mean() const {
}

Expression Gaussian::ToSymbolic() const {
std::normal_distribution<Expression> distribution(mean, std);
std::normal_distribution<Expression> distribution(mean, stddev);
return distribution();
}

Expand Down Expand Up @@ -225,25 +225,25 @@ GaussianVector<Size>::GaussianVector() {}
template <int Size>
GaussianVector<Size>::GaussianVector(
const drake::Vector<double, Size>& mean_in,
const drake::VectorX<double>& std_in)
const drake::VectorX<double>& stddev_in)
: mean(mean_in),
std(std_in) {}
stddev(stddev_in) {}

template <int Size>
GaussianVector<Size>::~GaussianVector() {}

template <int Size>
Eigen::VectorXd GaussianVector<Size>::Sample(
drake::RandomGenerator* generator) const {
if (!(std.size() == mean.size() || std.size() == 1)) {
if (!(stddev.size() == mean.size() || stddev.size() == 1)) {
throw std::logic_error(fmt::format(
"Cannot Sample() a GaussianVector distribution with "
"size {} mean but size {} dev", mean.size(), std.size()));
"size {} mean but size {} dev", mean.size(), stddev.size()));
}
Eigen::VectorXd result(mean.size());
for (int i = 0; i < mean.size(); ++i) {
const double std_i = (std.size() == 1) ? std(0) : std(i);
result(i) = Gaussian(mean(i), std_i).Sample(generator);
const double stddev_i = (stddev.size() == 1) ? stddev(0) : stddev(i);
result(i) = Gaussian(mean(i), stddev_i).Sample(generator);
}
return result;
}
Expand All @@ -255,15 +255,15 @@ Eigen::VectorXd GaussianVector<Size>::Mean() const {

template <int Size>
drake::VectorX<Expression> GaussianVector<Size>::ToSymbolic() const {
if (!(std.size() == mean.size() || std.size() == 1)) {
if (!(stddev.size() == mean.size() || stddev.size() == 1)) {
throw std::logic_error(fmt::format(
"Cannot ToSymbolic() a GaussianVector distribution with "
"size {} mean but size {} dev", mean.size(), std.size()));
"size {} mean but size {} dev", mean.size(), stddev.size()));
}
drake::VectorX<Expression> result(mean.size());
for (int i = 0; i < mean.size(); ++i) {
const double std_i = (std.size() == 1) ? std(0) : std(i);
result(i) = Gaussian(mean(i), std_i).ToSymbolic();
const double stddev_i = (stddev.size() == 1) ? stddev(0) : stddev(i);
result(i) = Gaussian(mean(i), stddev_i).ToSymbolic();
}
return result;
}
Expand Down Expand Up @@ -329,7 +329,7 @@ bool IsDeterministic(const DistributionVariant& var) {
return true;
},
[](const Gaussian& arg) -> bool {
return arg.std == 0.0;
return arg.stddev == 0.0;
},
[](const Uniform& arg) -> bool {
return arg.min == arg.max;
Expand Down Expand Up @@ -376,7 +376,7 @@ unique_ptr<DistributionVector> ToDistributionVector(
[](const Gaussian& arg) -> unique_ptr<DistributionVector> {
return std::make_unique<GaussianVector<Size>>(
Eigen::VectorXd::Constant(1, arg.mean),
Eigen::VectorXd::Constant(1, arg.std));
Eigen::VectorXd::Constant(1, arg.stddev));
},
[](const Uniform& arg) -> unique_ptr<DistributionVector> {
return std::make_unique<UniformVector<Size>>(
Expand All @@ -400,7 +400,7 @@ bool IsDeterministic(const DistributionVectorVariant<Size>& vec) {
return true;
},
[](const GaussianVector<Size>& arg) -> bool {
return arg.std.isZero(0.0);
return arg.stddev.isZero(0.0);
},
[](const UniformVector<Size>& arg) -> bool {
return arg.min == arg.max;
Expand All @@ -409,7 +409,7 @@ bool IsDeterministic(const DistributionVectorVariant<Size>& vec) {
return true;
},
[](const Gaussian& arg) -> bool {
return arg.std == 0.0;
return arg.stddev == 0.0;
},
[](const Uniform& arg) -> bool {
return arg.min == arg.max;
Expand Down
20 changes: 10 additions & 10 deletions common/schema/dev/stochastic.h
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ Whether fixed or dynamic size, you might specify stochastic variables:
thing:
value: !GaussianVector
mean: [2.1, 2.2, 2.3]
std: [1.0] # Same stddev each.
stddev: [1.0] # Same stddev each.
```

Or:
Expand All @@ -154,7 +154,7 @@ Whether fixed or dynamic size, you might specify stochastic variables:
thing:
value: !GaussianVector
mean: [2.1, 2.2, 2.3]
std: [1.0, 0.5, 0.2] # Different stddev each.
stddev: [1.0, 0.5, 0.2] # Different stddev each.
```

Or:
Expand Down Expand Up @@ -230,12 +230,12 @@ struct Deterministic final : public Distribution {
double value{};
};

/// A gaussian distribution with `mean` and `std`.
/// A gaussian distribution with `mean` and `stddev`.
struct Gaussian final : public Distribution {
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(Gaussian)

Gaussian();
Gaussian(double mean, double std);
Gaussian(double mean, double stddev);
~Gaussian() final;

double Sample(drake::RandomGenerator*) const final;
Expand All @@ -245,11 +245,11 @@ struct Gaussian final : public Distribution {
template <typename Archive>
void Serialize(Archive* a) {
a->Visit(DRAKE_NVP(mean));
a->Visit(DRAKE_NVP(std));
a->Visit(DRAKE_NVP(stddev));
}

double mean{};
double std{};
double stddev{};
};

/// A uniform distribution with `min` inclusive and `max` exclusive.
Expand Down Expand Up @@ -371,15 +371,15 @@ struct DeterministicVector final : public DistributionVector {
drake::Vector<double, Size> value;
};

/// A gaussian distribution with vector `mean` and vector or scalar `std`.
/// A gaussian distribution with vector `mean` and vector or scalar `stddev`.
/// @tparam Size rows at compile time (max 6) or else Eigen::Dynamic.
template <int Size>
struct GaussianVector final : public DistributionVector {
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(GaussianVector)

GaussianVector();
GaussianVector(const drake::Vector<double, Size>& mean,
const drake::VectorX<double>& std);
const drake::VectorX<double>& stddev);
~GaussianVector() final;

Eigen::VectorXd Sample(drake::RandomGenerator*) const final;
Expand All @@ -389,11 +389,11 @@ struct GaussianVector final : public DistributionVector {
template <typename Archive>
void Serialize(Archive* a) {
a->Visit(DRAKE_NVP(mean));
a->Visit(DRAKE_NVP(std));
a->Visit(DRAKE_NVP(stddev));
}

drake::Vector<double, Size> mean;
drake::VectorX<double> std;
drake::VectorX<double> stddev;
};

/// A uniform distribution with vector `min` inclusive and vector `max`
Expand Down
18 changes: 9 additions & 9 deletions common/schema/dev/test/stochastic_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,20 +33,20 @@ struct DistributionStruct {

const char* all_variants = R"""(
vec: [ !Deterministic { value: 5.0 },
!Gaussian { mean: 2.0, std: 4.0 },
!Gaussian { mean: 2.0, stddev: 4.0 },
!Uniform { min: 1.0, max: 5.0 },
!UniformDiscrete { values: [1, 1.5, 2] },
3.2 ]
)""";

const char* floats = "vec: [5.0, 6.1, 7.2]";

void CheckGaussianSymbolic(const Expression& e, double mean, double std) {
void CheckGaussianSymbolic(const Expression& e, double mean, double stddev) {
const Variables vars{e.GetVariables()};
ASSERT_EQ(vars.size(), 1);
const Variable& v{*(vars.begin())};
EXPECT_EQ(v.get_type(), Variable::Type::RANDOM_GAUSSIAN);
EXPECT_PRED2(ExprEqual, e, mean + std * v);
EXPECT_PRED2(ExprEqual, e, mean + stddev * v);
}

void CheckUniformSymbolic(const Expression& e, double min, double max) {
Expand Down Expand Up @@ -82,9 +82,9 @@ GTEST_TEST(StochasticTest, ScalarTest) {

const Gaussian& g = std::get<Gaussian>(variants.vec[1]);
EXPECT_EQ(g.mean, 2.);
EXPECT_EQ(g.std, 4.);
EXPECT_EQ(g.stddev, 4.);
EXPECT_EQ(g.Mean(), 2.);
CheckGaussianSymbolic(g.ToSymbolic(), g.mean, g.std);
CheckGaussianSymbolic(g.ToSymbolic(), g.mean, g.stddev);
EXPECT_FALSE(IsDeterministic(variants.vec[1]));
EXPECT_THROW(GetDeterministicValue(variants.vec[1]),
std::logic_error);
Expand Down Expand Up @@ -140,7 +140,7 @@ GTEST_TEST(StochasticTest, ScalarTest) {
VectorX<Expression> symbolic_vec = ToSymbolic(variants.vec);
ASSERT_EQ(symbolic_vec.size(), 5);
EXPECT_PRED2(ExprEqual, symbolic_vec(0), 5.0);
CheckGaussianSymbolic(symbolic_vec(1), g.mean, g.std);
CheckGaussianSymbolic(symbolic_vec(1), g.mean, g.stddev);
CheckUniformSymbolic(symbolic_vec(2), u.min, u.max);
CheckUniformDiscreteSymbolic(symbolic_vec(3), ub.values);
EXPECT_PRED2(ExprEqual, symbolic_vec(4), 3.2);
Expand Down Expand Up @@ -178,11 +178,11 @@ struct DistributionVectorStruct {
const char* vector_variants = R"""(
vector: [1., 2., 3.]
deterministic: !DeterministicVector { value: [3., 4., 5.] }
gaussian1: !GaussianVector { mean: [1.1, 1.2, 1.3], std: [0.1, 0.2, 0.3] }
gaussian2: !GaussianVector { mean: [2.1, 2.2, 2.3, 2.4], std: [1.0] }
gaussian1: !GaussianVector { mean: [1.1, 1.2, 1.3], stddev: [0.1, 0.2, 0.3] }
gaussian2: !GaussianVector { mean: [2.1, 2.2, 2.3, 2.4], stddev: [1.0] }
uniform: !UniformVector { min: [10, 20], max: [11, 22] }
deterministic_scalar: !Deterministic { value: 19.5 }
gaussian_scalar: !Gaussian { mean: 5, std: 1 }
gaussian_scalar: !Gaussian { mean: 5, stddev: 1 }
uniform_scalar: !Uniform { min: 1, max: 2 }
)""";

Expand Down