Use new constructors
parent
e690ff817a
commit
85e57f1c20
|
|
@ -44,9 +44,14 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet<HybridConditional> {
|
||||||
/// @name Standard Constructors
|
/// @name Standard Constructors
|
||||||
/// @{
|
/// @{
|
||||||
|
|
||||||
/** Construct empty Bayes net */
|
/// Construct empty Bayes net.
|
||||||
HybridBayesNet() = default;
|
HybridBayesNet() = default;
|
||||||
|
|
||||||
|
/// Constructor that takes an initializer list of shared pointers.
|
||||||
|
HybridBayesNet(
|
||||||
|
std::initializer_list<HybridConditional::shared_ptr> conditionals)
|
||||||
|
: Base(conditionals) {}
|
||||||
|
|
||||||
/// @}
|
/// @}
|
||||||
/// @name Testable
|
/// @name Testable
|
||||||
/// @{
|
/// @{
|
||||||
|
|
|
||||||
|
|
@ -20,6 +20,7 @@
|
||||||
|
|
||||||
#include <gtsam/hybrid/HybridBayesNet.h>
|
#include <gtsam/hybrid/HybridBayesNet.h>
|
||||||
#include <gtsam/hybrid/HybridBayesTree.h>
|
#include <gtsam/hybrid/HybridBayesTree.h>
|
||||||
|
#include <gtsam/hybrid/HybridConditional.h>
|
||||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||||
|
|
||||||
|
|
@ -32,7 +33,6 @@
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
|
|
||||||
using noiseModel::Isotropic;
|
|
||||||
using symbol_shorthand::M;
|
using symbol_shorthand::M;
|
||||||
using symbol_shorthand::X;
|
using symbol_shorthand::X;
|
||||||
using symbol_shorthand::Z;
|
using symbol_shorthand::Z;
|
||||||
|
|
@ -92,39 +92,51 @@ TEST(HybridBayesNet, Tiny) {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ****************************************************************************/
|
/* ****************************************************************************/
|
||||||
// Test evaluate for a hybrid Bayes net P(X0|X1) P(X1|Asia) P(Asia).
|
// Hybrid Bayes net P(X0|X1) P(X1|Asia) P(Asia).
|
||||||
TEST(HybridBayesNet, evaluateHybrid) {
|
namespace different_sigmas {
|
||||||
const auto continuousConditional = GaussianConditional::sharedMeanAndStddev(
|
const auto gc = GaussianConditional::sharedMeanAndStddev(X(0), 2 * I_1x1, X(1),
|
||||||
X(0), 2 * I_1x1, X(1), Vector1(-4.0), 5.0);
|
Vector1(-4.0), 5.0);
|
||||||
|
|
||||||
const SharedDiagonal model0 = noiseModel::Diagonal::Sigmas(Vector1(2.0)),
|
const std::vector<std::pair<Vector, double>> parms{{Vector1(5), 2.0},
|
||||||
model1 = noiseModel::Diagonal::Sigmas(Vector1(3.0));
|
{Vector1(2), 3.0}};
|
||||||
|
const auto hgc = std::make_shared<HybridGaussianConditional>(X(1), Asia, parms);
|
||||||
|
|
||||||
const auto conditional0 = std::make_shared<GaussianConditional>(
|
const auto prior = std::make_shared<DiscreteConditional>(Asia, "99/1");
|
||||||
X(1), Vector1::Constant(5), I_1x1, model0),
|
auto wrap = [](const auto& c) {
|
||||||
conditional1 = std::make_shared<GaussianConditional>(
|
return std::make_shared<HybridConditional>(c);
|
||||||
X(1), Vector1::Constant(2), I_1x1, model1);
|
};
|
||||||
|
const HybridBayesNet bayesNet{wrap(gc), wrap(hgc), wrap(prior)};
|
||||||
// Create hybrid Bayes net.
|
|
||||||
HybridBayesNet bayesNet;
|
|
||||||
bayesNet.push_back(continuousConditional);
|
|
||||||
bayesNet.emplace_shared<HybridGaussianConditional>(
|
|
||||||
Asia, std::vector{conditional0, conditional1});
|
|
||||||
bayesNet.emplace_shared<DiscreteConditional>(Asia, "99/1");
|
|
||||||
|
|
||||||
// Create values at which to evaluate.
|
// Create values at which to evaluate.
|
||||||
HybridValues values;
|
HybridValues values{{{X(0), Vector1(-6)}, {X(1), Vector1(1)}}, {{asiaKey, 0}}};
|
||||||
values.insert(asiaKey, 0);
|
} // namespace different_sigmas
|
||||||
values.insert(X(0), Vector1(-6));
|
|
||||||
values.insert(X(1), Vector1(1));
|
|
||||||
|
|
||||||
const double conditionalProbability =
|
/* ****************************************************************************/
|
||||||
continuousConditional->evaluate(values.continuous());
|
// Test evaluate for a hybrid Bayes net P(X0|X1) P(X1|Asia) P(Asia).
|
||||||
const double mixtureProbability = conditional0->evaluate(values.continuous());
|
TEST(HybridBayesNet, evaluateHybrid) {
|
||||||
|
using namespace different_sigmas;
|
||||||
|
|
||||||
|
const double conditionalProbability = gc->evaluate(values.continuous());
|
||||||
|
const double mixtureProbability = hgc->evaluate(values);
|
||||||
EXPECT_DOUBLES_EQUAL(conditionalProbability * mixtureProbability * 0.99,
|
EXPECT_DOUBLES_EQUAL(conditionalProbability * mixtureProbability * 0.99,
|
||||||
bayesNet.evaluate(values), 1e-9);
|
bayesNet.evaluate(values), 1e-9);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ****************************************************************************/
|
||||||
|
// Test error for a hybrid Bayes net P(X0|X1) P(X1|Asia) P(Asia).
|
||||||
|
TEST(HybridBayesNet, Error) {
|
||||||
|
using namespace different_sigmas;
|
||||||
|
|
||||||
|
AlgebraicDecisionTree<Key> actual = bayesNet.errorTree(values.continuous());
|
||||||
|
|
||||||
|
// Regression.
|
||||||
|
// Manually added all the error values from the 3 conditional types.
|
||||||
|
AlgebraicDecisionTree<Key> expected(
|
||||||
|
{Asia}, std::vector<double>{2.33005033585, 5.38619084965});
|
||||||
|
|
||||||
|
EXPECT(assert_equal(expected, actual));
|
||||||
|
}
|
||||||
|
|
||||||
/* ****************************************************************************/
|
/* ****************************************************************************/
|
||||||
// Test choosing an assignment of conditionals
|
// Test choosing an assignment of conditionals
|
||||||
TEST(HybridBayesNet, Choose) {
|
TEST(HybridBayesNet, Choose) {
|
||||||
|
|
@ -154,45 +166,6 @@ TEST(HybridBayesNet, Choose) {
|
||||||
*gbn.at(3)));
|
*gbn.at(3)));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ****************************************************************************/
|
|
||||||
// Test error for a hybrid Bayes net P(X0|X1) P(X1|Asia) P(Asia).
|
|
||||||
TEST(HybridBayesNet, Error) {
|
|
||||||
const auto continuousConditional = GaussianConditional::sharedMeanAndStddev(
|
|
||||||
X(0), 2 * I_1x1, X(1), Vector1(-4.0), 5.0);
|
|
||||||
|
|
||||||
const SharedDiagonal model0 = noiseModel::Diagonal::Sigmas(Vector1(2.0)),
|
|
||||||
model1 = noiseModel::Diagonal::Sigmas(Vector1(3.0));
|
|
||||||
|
|
||||||
const auto conditional0 = std::make_shared<GaussianConditional>(
|
|
||||||
X(1), Vector1::Constant(5), I_1x1, model0),
|
|
||||||
conditional1 = std::make_shared<GaussianConditional>(
|
|
||||||
X(1), Vector1::Constant(2), I_1x1, model1);
|
|
||||||
|
|
||||||
auto gm = std::make_shared<HybridGaussianConditional>(
|
|
||||||
Asia, std::vector{conditional0, conditional1});
|
|
||||||
// Create hybrid Bayes net.
|
|
||||||
HybridBayesNet bayesNet;
|
|
||||||
bayesNet.push_back(continuousConditional);
|
|
||||||
bayesNet.push_back(gm);
|
|
||||||
bayesNet.emplace_shared<DiscreteConditional>(Asia, "99/1");
|
|
||||||
|
|
||||||
// Create values at which to evaluate.
|
|
||||||
HybridValues values;
|
|
||||||
values.insert(asiaKey, 0);
|
|
||||||
values.insert(X(0), Vector1(-6));
|
|
||||||
values.insert(X(1), Vector1(1));
|
|
||||||
|
|
||||||
AlgebraicDecisionTree<Key> actual_errors =
|
|
||||||
bayesNet.errorTree(values.continuous());
|
|
||||||
|
|
||||||
// Regression.
|
|
||||||
// Manually added all the error values from the 3 conditional types.
|
|
||||||
AlgebraicDecisionTree<Key> expected_errors(
|
|
||||||
{Asia}, std::vector<double>{2.33005033585, 5.38619084965});
|
|
||||||
|
|
||||||
EXPECT(assert_equal(expected_errors, actual_errors));
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ****************************************************************************/
|
/* ****************************************************************************/
|
||||||
// Test Bayes net optimize
|
// Test Bayes net optimize
|
||||||
TEST(HybridBayesNet, OptimizeAssignment) {
|
TEST(HybridBayesNet, OptimizeAssignment) {
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue