Classes | |
class | Deterministic |
A single deterministic value . More... | |
class | DeterministicVector |
A single deterministic vector value . More... | |
class | Distribution |
Base class for a single distribution, to be used with YAML archives. More... | |
class | DistributionVector |
Base class for a vector of distributions, to be used with YAML archives. More... | |
class | Gaussian |
A gaussian distribution with mean and stddev . More... | |
class | GaussianVector |
A gaussian distribution with vector mean and vector or scalar stddev . More... | |
class | Rotation |
A specification for an SO(3) rotation, to be used for serialization purposes, e.g., to define stochastic scenarios. More... | |
class | Transform |
A specification for a 3d rotation and translation, optionally with respect to a base frame. More... | |
class | Uniform |
A uniform distribution with min inclusive and max exclusive. More... | |
class | UniformDiscrete |
Chooses from among discrete values with equal probability. More... | |
class | UniformVector |
A uniform distribution with vector min inclusive and vector max exclusive. More... | |
Typedefs | |
using | DistributionVariant = std::variant< double, Deterministic, Gaussian, Uniform, UniformDiscrete > |
Variant over all kinds of distributions. More... | |
template<int Size> | |
using | DistributionVectorVariant = std::variant< drake::Vector< double, Size >, DeterministicVector< Size >, GaussianVector< Size >, UniformVector< Size >, std::conditional_t<(Size==Eigen::Dynamic||Size==1), Deterministic, internal::InvalidVariantSelection< Deterministic > >, std::conditional_t<(Size==Eigen::Dynamic||Size==1), Gaussian, internal::InvalidVariantSelection< Gaussian > >, std::conditional_t<(Size==Eigen::Dynamic||Size==1), Uniform, internal::InvalidVariantSelection< Uniform > >> |
Variant over all kinds of vector distributions. More... | |
using | DistributionVectorVariantX = DistributionVectorVariant< Eigen::Dynamic > |
DistributionVectorVariant that permits any vector size dynamically. More... | |
Functions | |
std::unique_ptr< Distribution > | ToDistribution (const DistributionVariant &var) |
Copies the given variant into a Distribution base class. More... | |
double | Sample (const DistributionVariant &var, drake::RandomGenerator *generator) |
Like Distribution::Sample, but on a DistributionVariant instead. More... | |
double | Mean (const DistributionVariant &var) |
Like Distribution::Mean, but on a DistributionVariant instead. More... | |
drake::symbolic::Expression | ToSymbolic (const DistributionVariant &var) |
Like Distribution::ToSymbolic, but on a DistributionVariant instead. More... | |
Eigen::VectorXd | Sample (const std::vector< DistributionVariant > &vec, drake::RandomGenerator *generator) |
Like Distribution::Sample, but elementwise over a collection of possibly-heterogenous DistributionVariant instead. More... | |
Eigen::VectorXd | Mean (const std::vector< DistributionVariant > &vec) |
Like Distribution::Mean, but elementwise over a collection of possibly-heterogenous DistributionVariant instead. More... | |
drake::VectorX< drake::symbolic::Expression > | ToSymbolic (const std::vector< DistributionVariant > &vec) |
Like Distribution::ToSymbolic, but elementwise over a collection of possibly-heterogenous DistributionVariant instead. More... | |
bool | IsDeterministic (const DistributionVariant &var) |
Returns true iff var is set to a deterministic value. More... | |
double | GetDeterministicValue (const DistributionVariant &var) |
If var is deterministic, retrieves its value. More... | |
template<int Size> | |
std::unique_ptr< DistributionVector > | ToDistributionVector (const DistributionVectorVariant< Size > &vec) |
Copies the given variant into a DistributionVector base class. More... | |
template<int Size> | |
bool | IsDeterministic (const DistributionVectorVariant< Size > &vec) |
Returns true iff all of vec 's elements are set to a deterministic value. More... | |
template<int Size> | |
Eigen::VectorXd | GetDeterministicValue (const DistributionVectorVariant< Size > &vec) |
If vec is deterministic, retrieves its value. More... | |
using DistributionVariant = std::variant< double, Deterministic, Gaussian, Uniform, UniformDiscrete> |
Variant over all kinds of distributions.
using DistributionVectorVariant = std::variant< drake::Vector<double, Size>, DeterministicVector<Size>, GaussianVector<Size>, UniformVector<Size>, std::conditional_t<(Size == Eigen::Dynamic || Size == 1), Deterministic, internal::InvalidVariantSelection<Deterministic> >, std::conditional_t<(Size == Eigen::Dynamic || Size == 1), Gaussian, internal::InvalidVariantSelection<Gaussian> >, std::conditional_t<(Size == Eigen::Dynamic || Size == 1), Uniform, internal::InvalidVariantSelection<Uniform> >> |
Variant over all kinds of vector distributions.
If the Size parameter allows for 1-element vectors (i.e, is either 1 or Eigen::Dynamic), then this variant also offers the single distribution types (Deterministic, Gaussian, Uniform). If the Size parameter is 2 or greater, the single distribution types are not allowed.
Size | rows at compile time (max 6) or else Eigen::Dynamic. |
using DistributionVectorVariantX = DistributionVectorVariant<Eigen::Dynamic> |
DistributionVectorVariant that permits any vector size dynamically.
double drake::schema::GetDeterministicValue | ( | const DistributionVariant & | var | ) |
If var
is deterministic, retrieves its value.
std::exception | if var is not deterministic. |
Eigen::VectorXd drake::schema::GetDeterministicValue | ( | const DistributionVectorVariant< Size > & | vec | ) |
If vec
is deterministic, retrieves its value.
std::exception | if vec is not deterministic. |
Size | rows at compile time (max 6) or else Eigen::Dynamic. |
bool drake::schema::IsDeterministic | ( | const DistributionVariant & | var | ) |
Returns true iff var
is set to a deterministic value.
bool drake::schema::IsDeterministic | ( | const DistributionVectorVariant< Size > & | vec | ) |
Returns true iff all of vec
's elements are set to a deterministic value.
Size | rows at compile time (max 6) or else Eigen::Dynamic. |
double drake::schema::Mean | ( | const DistributionVariant & | var | ) |
Like Distribution::Mean, but on a DistributionVariant instead.
Eigen::VectorXd drake::schema::Mean | ( | const std::vector< DistributionVariant > & | vec | ) |
Like Distribution::Mean, but elementwise over a collection of possibly-heterogenous DistributionVariant instead.
double drake::schema::Sample | ( | const DistributionVariant & | var, |
drake::RandomGenerator * | generator | ||
) |
Like Distribution::Sample, but on a DistributionVariant instead.
Eigen::VectorXd drake::schema::Sample | ( | const std::vector< DistributionVariant > & | vec, |
drake::RandomGenerator * | generator | ||
) |
Like Distribution::Sample, but elementwise over a collection of possibly-heterogenous DistributionVariant instead.
std::unique_ptr<Distribution> drake::schema::ToDistribution | ( | const DistributionVariant & | var | ) |
Copies the given variant into a Distribution base class.
std::unique_ptr<DistributionVector> drake::schema::ToDistributionVector | ( | const DistributionVectorVariant< Size > & | vec | ) |
Copies the given variant into a DistributionVector base class.
Size | rows at compile time (max 6) or else Eigen::Dynamic. |
drake::symbolic::Expression drake::schema::ToSymbolic | ( | const DistributionVariant & | var | ) |
Like Distribution::ToSymbolic, but on a DistributionVariant instead.
drake::VectorX<drake::symbolic::Expression> drake::schema::ToSymbolic | ( | const std::vector< DistributionVariant > & | vec | ) |
Like Distribution::ToSymbolic, but elementwise over a collection of possibly-heterogenous DistributionVariant instead.