add incremental pruning to HybridGaussianISAM

release/4.3a0
Varun Agrawal 2022-08-16 17:23:52 -04:00
parent 77bea319dd
commit ac20cff710
5 changed files with 449 additions and 363 deletions

View File

@ -119,11 +119,36 @@ void GaussianMixture::print(const std::string &s,
"", [&](Key k) { return formatter(k); }, "", [&](Key k) { return formatter(k); },
[&](const GaussianConditional::shared_ptr &gf) -> std::string { [&](const GaussianConditional::shared_ptr &gf) -> std::string {
RedirectCout rd; RedirectCout rd;
if (!gf->empty()) if (gf && !gf->empty())
gf->print("", formatter); gf->print("", formatter);
else else
return {"nullptr"}; return {"nullptr"};
return rd.str(); return rd.str();
}); });
} }
/* *******************************************************************************/
void GaussianMixture::prune(const DecisionTreeFactor &decisionTree) {
// Functional which loops over all assignments and create a set of
// GaussianConditionals
auto pruner = [&decisionTree](
const Assignment<Key> &choices,
const GaussianConditional::shared_ptr &conditional)
-> GaussianConditional::shared_ptr {
// typecast so we can use this to get probability value
DiscreteValues values(choices);
if (decisionTree(values) == 0.0) {
// empty aka null pointer
boost::shared_ptr<GaussianConditional> null;
return null;
} else {
return conditional;
}
};
auto pruned_conditionals = conditionals_.apply(pruner);
conditionals_.root_ = pruned_conditionals.root_;
}
} // namespace gtsam } // namespace gtsam

View File

@ -21,6 +21,7 @@
#include <gtsam/discrete/DecisionTree-inl.h> #include <gtsam/discrete/DecisionTree-inl.h>
#include <gtsam/discrete/DecisionTree.h> #include <gtsam/discrete/DecisionTree.h>
#include <gtsam/discrete/DecisionTreeFactor.h>
#include <gtsam/discrete/DiscreteKey.h> #include <gtsam/discrete/DiscreteKey.h>
#include <gtsam/hybrid/HybridFactor.h> #include <gtsam/hybrid/HybridFactor.h>
#include <gtsam/inference/Conditional.h> #include <gtsam/inference/Conditional.h>
@ -121,7 +122,7 @@ class GTSAM_EXPORT GaussianMixture
/// Test equality with base HybridFactor /// Test equality with base HybridFactor
bool equals(const HybridFactor &lf, double tol = 1e-9) const override; bool equals(const HybridFactor &lf, double tol = 1e-9) const override;
/* print utility */ /// Print utility
void print( void print(
const std::string &s = "GaussianMixture\n", const std::string &s = "GaussianMixture\n",
const KeyFormatter &formatter = DefaultKeyFormatter) const override; const KeyFormatter &formatter = DefaultKeyFormatter) const override;
@ -131,6 +132,15 @@ class GTSAM_EXPORT GaussianMixture
/// Getter for the underlying Conditionals DecisionTree /// Getter for the underlying Conditionals DecisionTree
const Conditionals &conditionals(); const Conditionals &conditionals();
/**
* @brief Prune the decision tree of Gaussian factors as per the discrete
* `decisionTree`.
*
* @param decisionTree A pruned decision tree of discrete keys where the
* leaves are probabilities.
*/
void prune(const DecisionTreeFactor &decisionTree);
/** /**
* @brief Merge the Gaussian Factor Graphs in `this` and `sum` while * @brief Merge the Gaussian Factor Graphs in `this` and `sum` while
* maintaining the decision tree structure. * maintaining the decision tree structure.

View File

@ -41,6 +41,7 @@ HybridGaussianISAM::HybridGaussianISAM(const HybridBayesTree& bayesTree)
void HybridGaussianISAM::updateInternal( void HybridGaussianISAM::updateInternal(
const HybridGaussianFactorGraph& newFactors, const HybridGaussianFactorGraph& newFactors,
HybridBayesTree::Cliques* orphans, HybridBayesTree::Cliques* orphans,
const boost::optional<Ordering>& ordering,
const HybridBayesTree::Eliminate& function) { const HybridBayesTree::Eliminate& function) {
// Remove the contaminated part of the Bayes tree // Remove the contaminated part of the Bayes tree
BayesNetType bn; BayesNetType bn;
@ -78,12 +79,19 @@ void HybridGaussianISAM::updateInternal(
// Get an ordering where the new keys are eliminated last // Get an ordering where the new keys are eliminated last
const VariableIndex index(factors); const VariableIndex index(factors);
const Ordering ordering = Ordering::ColamdConstrainedLast( Ordering elimination_ordering;
index, KeyVector(newKeysDiscreteLast.begin(), newKeysDiscreteLast.end()), if (ordering) {
true); elimination_ordering = *ordering;
} else {
elimination_ordering = Ordering::ColamdConstrainedLast(
index,
KeyVector(newKeysDiscreteLast.begin(), newKeysDiscreteLast.end()),
true);
}
// eliminate all factors (top, added, orphans) into a new Bayes tree // eliminate all factors (top, added, orphans) into a new Bayes tree
auto bayesTree = factors.eliminateMultifrontal(ordering, function, index); HybridBayesTree::shared_ptr bayesTree =
factors.eliminateMultifrontal(elimination_ordering, function, index);
// Re-add into Bayes tree data structures // Re-add into Bayes tree data structures
this->roots_.insert(this->roots_.end(), bayesTree->roots().begin(), this->roots_.insert(this->roots_.end(), bayesTree->roots().begin(),
@ -93,9 +101,45 @@ void HybridGaussianISAM::updateInternal(
/* ************************************************************************* */ /* ************************************************************************* */
void HybridGaussianISAM::update(const HybridGaussianFactorGraph& newFactors, void HybridGaussianISAM::update(const HybridGaussianFactorGraph& newFactors,
const boost::optional<Ordering>& ordering,
const HybridBayesTree::Eliminate& function) { const HybridBayesTree::Eliminate& function) {
Cliques orphans; Cliques orphans;
this->updateInternal(newFactors, &orphans, function); this->updateInternal(newFactors, &orphans, ordering, function);
}
void HybridGaussianISAM::prune(const Key& root, const size_t maxNrLeaves) {
auto decisionTree = boost::dynamic_pointer_cast<DecisionTreeFactor>(
this->clique(root)->conditional()->inner());
DecisionTreeFactor prunedDiscreteFactor = decisionTree->prune(maxNrLeaves);
decisionTree->root_ = prunedDiscreteFactor.root_;
std::vector<gtsam::Key> prunedKeys;
for (auto&& clique : nodes()) {
// The cliques can be repeated for each frontal so we record it in
// prunedKeys and check if we have already pruned a particular clique.
if (std::find(prunedKeys.begin(), prunedKeys.end(), clique.first) !=
prunedKeys.end()) {
continue;
}
// Add all the keys of the current clique to be pruned to prunedKeys
for (auto&& key : clique.second->conditional()->frontals()) {
prunedKeys.push_back(key);
}
// Convert parents() to a KeyVector for comparison
KeyVector parents;
for (auto&& parent : clique.second->conditional()->parents()) {
parents.push_back(parent);
}
if (parents == decisionTree->keys()) {
auto gaussianMixture = boost::dynamic_pointer_cast<GaussianMixture>(
clique.second->conditional()->inner());
gaussianMixture->prune(prunedDiscreteFactor);
}
}
} }
} // namespace gtsam } // namespace gtsam

View File

@ -48,6 +48,7 @@ class GTSAM_EXPORT HybridGaussianISAM : public ISAM<HybridBayesTree> {
void updateInternal( void updateInternal(
const HybridGaussianFactorGraph& newFactors, const HybridGaussianFactorGraph& newFactors,
HybridBayesTree::Cliques* orphans, HybridBayesTree::Cliques* orphans,
const boost::optional<Ordering>& ordering = boost::none,
const HybridBayesTree::Eliminate& function = const HybridBayesTree::Eliminate& function =
HybridBayesTree::EliminationTraitsType::DefaultEliminate); HybridBayesTree::EliminationTraitsType::DefaultEliminate);
@ -59,8 +60,17 @@ class GTSAM_EXPORT HybridGaussianISAM : public ISAM<HybridBayesTree> {
* @param function Elimination function. * @param function Elimination function.
*/ */
void update(const HybridGaussianFactorGraph& newFactors, void update(const HybridGaussianFactorGraph& newFactors,
const boost::optional<Ordering>& ordering = boost::none,
const HybridBayesTree::Eliminate& function = const HybridBayesTree::Eliminate& function =
HybridBayesTree::EliminationTraitsType::DefaultEliminate); HybridBayesTree::EliminationTraitsType::DefaultEliminate);
/**
* @brief
*
* @param root The root key in the discrete conditional decision tree.
* @param maxNumberLeaves
*/
void prune(const Key& root, const size_t maxNumberLeaves);
}; };
/// traits /// traits

View File

@ -52,10 +52,10 @@ TEST(HybridGaussianElimination, IncrementalElimination) {
HybridGaussianFactorGraph graph1; HybridGaussianFactorGraph graph1;
// Create initial factor graph // Create initial factor graph
// * * * // * * *
// | | | // | | |
// *- X1 -*- X2 -*- X3 // X1 -*- X2 -*- X3
// \*-M1-*/ // \*-M1-*/
graph1.push_back(switching.linearizedFactorGraph.at(0)); // P(X1) graph1.push_back(switching.linearizedFactorGraph.at(0)); // P(X1)
graph1.push_back(switching.linearizedFactorGraph.at(1)); // P(X1, X2 | M1) graph1.push_back(switching.linearizedFactorGraph.at(1)); // P(X1, X2 | M1)
graph1.push_back(switching.linearizedFactorGraph.at(2)); // P(X2, X3 | M2) graph1.push_back(switching.linearizedFactorGraph.at(2)); // P(X2, X3 | M2)
@ -179,7 +179,8 @@ TEST(HybridGaussianElimination, IncrementalInference) {
DiscreteValues m00; DiscreteValues m00;
m00[M(1)] = 0, m00[M(2)] = 0; m00[M(1)] = 0, m00[M(2)] = 0;
DiscreteConditional decisionTree = *(*discreteBayesTree)[M(2)]->conditional()->asDiscreteConditional(); DiscreteConditional decisionTree =
*(*discreteBayesTree)[M(2)]->conditional()->asDiscreteConditional();
double m00_prob = decisionTree(m00); double m00_prob = decisionTree(m00);
auto discreteConditional = isam[M(2)]->conditional()->asDiscreteConditional(); auto discreteConditional = isam[M(2)]->conditional()->asDiscreteConditional();
@ -200,8 +201,8 @@ TEST(HybridGaussianElimination, IncrementalInference) {
assignment[M(2)] = 1; assignment[M(2)] = 1;
EXPECT(assert_equal(0.2, (*discreteConditional)(assignment), 1e-5)); EXPECT(assert_equal(0.2, (*discreteConditional)(assignment), 1e-5));
// Check if the clique conditional generated from incremental elimination matches // Check if the clique conditional generated from incremental elimination
// that of batch elimination. // matches that of batch elimination.
auto expectedChordal = expectedRemainingGraph->eliminateMultifrontal(); auto expectedChordal = expectedRemainingGraph->eliminateMultifrontal();
auto expectedConditional = dynamic_pointer_cast<DecisionTreeFactor>( auto expectedConditional = dynamic_pointer_cast<DecisionTreeFactor>(
(*expectedChordal)[M(2)]->conditional()->inner()); (*expectedChordal)[M(2)]->conditional()->inner());
@ -213,419 +214,415 @@ TEST(HybridGaussianElimination, IncrementalInference) {
/* ****************************************************************************/ /* ****************************************************************************/
// Test if we can approximately do the inference // Test if we can approximately do the inference
TEST(HybridGaussianElimination, Approx_inference) { TEST(HybridGaussianElimination, Approx_inference) {
// Switching switching(4); Switching switching(4);
// IncrementalHybrid incrementalHybrid; HybridGaussianISAM incrementalHybrid;
// HybridGaussianFactorGraph graph1; HybridGaussianFactorGraph graph1;
// // Add the 3 DC factors, x1-x2, x2-x3, x3-x4 // Add the 3 hybrid factors, x1-x2, x2-x3, x3-x4
// for (size_t i = 0; i < 3; i++) { for (size_t i = 1; i < 4; i++) {
// graph1.push_back(switching.linearizedFactorGraph.dcGraph().at(i)); graph1.push_back(switching.linearizedFactorGraph.at(i));
// } }
// // Add the Gaussian factors, 1 prior on X(1), 4 measurements // Add the Gaussian factors, 1 prior on X(1),
// for (size_t i = 0; i <= 4; i++) { // 3 measurements on X(2), X(3), X(4)
// graph1.push_back(switching.linearizedFactorGraph.gaussianGraph().at(i)); graph1.push_back(switching.linearizedFactorGraph.at(0));
// } for (size_t i = 4; i <= 7; i++) {
graph1.push_back(switching.linearizedFactorGraph.at(i));
}
// // Create ordering. // Create ordering.
// Ordering ordering; Ordering ordering;
// for (size_t j = 1; j <= 4; j++) { for (size_t j = 1; j <= 4; j++) {
// ordering += X(j); ordering += X(j);
// } }
// // Now we calculate the actual factors using full elimination // Now we calculate the actual factors using full elimination
// HybridBayesNet::shared_ptr unprunedHybridBayesNet; HybridBayesTree::shared_ptr unprunedHybridBayesTree;
// HybridGaussianFactorGraph::shared_ptr unprunedRemainingGraph; HybridGaussianFactorGraph::shared_ptr unprunedRemainingGraph;
// std::tie(unprunedHybridBayesNet, unprunedRemainingGraph) = std::tie(unprunedHybridBayesTree, unprunedRemainingGraph) =
// switching.linearizedFactorGraph.eliminatePartialSequential(ordering); switching.linearizedFactorGraph.eliminatePartialMultifrontal(ordering);
// size_t maxComponents = 5; size_t maxNrLeaves = 5;
// incrementalHybrid.update(graph1, ordering, maxComponents); incrementalHybrid.update(graph1);
// /* incrementalHybrid.prune(M(3), maxNrLeaves);
// unpruned factor is:
// Choice(m3)
// 0 Choice(m2)
// 0 0 Choice(m1)
// 0 0 0 Leaf 0.2248 -
// 0 0 1 Leaf 0.3715 -
// 0 1 Choice(m1)
// 0 1 0 Leaf 0.3742 *
// 0 1 1 Leaf 0.6125 *
// 1 Choice(m2)
// 1 0 Choice(m1)
// 1 0 0 Leaf 0.3706 -
// 1 0 1 Leaf 0.6124 *
// 1 1 Choice(m1)
// 1 1 0 Leaf 0.611 *
// 1 1 1 Leaf 1 *
// pruned factors is: /*
// Choice(m3) unpruned factor is:
// 0 Choice(m2) Choice(m3)
// 0 0 Leaf 0 0 Choice(m2)
// 0 1 Choice(m1) 0 0 Choice(m1)
// 0 1 0 Leaf 0.3742 0 0 0 Leaf 0.11267528
// 0 1 1 Leaf 0.6125 0 0 1 Leaf 0.18576102
// 1 Choice(m2) 0 1 Choice(m1)
// 1 0 Choice(m1) 0 1 0 Leaf 0.18754662
// 1 0 0 Leaf 0 0 1 1 Leaf 0.30623871
// 1 0 1 Leaf 0.6124 1 Choice(m2)
// 1 1 Choice(m1) 1 0 Choice(m1)
// 1 1 0 Leaf 0.611 1 0 0 Leaf 0.18576102
// 1 1 1 Leaf 1 1 0 1 Leaf 0.30622428
// */ 1 1 Choice(m1)
1 1 0 Leaf 0.30623871
1 1 1 Leaf 0.5
// // Test that the remaining factor graph has one pruned factors is:
// // DecisionTreeFactor on {M3, M2, M1}. Choice(m3)
// auto remainingFactorGraph = incrementalHybrid.remainingFactorGraph(); 0 Choice(m2)
// EXPECT_LONGS_EQUAL(1, remainingFactorGraph.size()); 0 0 Leaf 0
0 1 Choice(m1)
0 1 0 Leaf 0.18754662
0 1 1 Leaf 0.30623871
1 Choice(m2)
1 0 Choice(m1)
1 0 0 Leaf 0
1 0 1 Leaf 0.30622428
1 1 Choice(m1)
1 1 0 Leaf 0.30623871
1 1 1 Leaf 0.5
*/
// auto discreteFactor_m1 = *dynamic_pointer_cast<DecisionTreeFactor>( auto discreteConditional_m1 = *dynamic_pointer_cast<DiscreteConditional>(
// incrementalHybrid.remainingDiscreteGraph().at(0)); incrementalHybrid[M(1)]->conditional()->inner());
// EXPECT(discreteFactor_m1.keys() == KeyVector({M(3), M(2), M(1)})); EXPECT(discreteConditional_m1.keys() == KeyVector({M(1), M(2), M(3)}));
// // Get the number of elements which are equal to 0. // Get the number of elements which are greater than 0.
// auto count = [](const double &value, int count) { auto count = [](const double &value, int count) {
// return value > 0 ? count + 1 : count; return value > 0 ? count + 1 : count;
// }; };
// // Check that the number of leaves after pruning is 5. // Check that the number of leaves after pruning is 5.
// EXPECT_LONGS_EQUAL(5, discreteFactor_m1.fold(count, 0)); EXPECT_LONGS_EQUAL(5, discreteConditional_m1.fold(count, 0));
// /* Expected hybrid Bayes net // Check that the hybrid nodes of the bayes net match those of the pre-pruning
// * factor 0: [x1 | x2 m1 ], 2 components // bayes net, at the same positions.
// * factor 1: [x2 | x3 m2 m1 ], 4 components auto &unprunedLastDensity = *dynamic_pointer_cast<GaussianMixture>(
// * factor 2: [x3 | x4 m3 m2 m1 ], 8 components unprunedHybridBayesTree->clique(X(4))->conditional()->inner());
// * factor 3: [x4 | m3 m2 m1 ], 8 components auto &lastDensity = *dynamic_pointer_cast<GaussianMixture>(
// */ incrementalHybrid[X(4)]->conditional()->inner());
// auto hybridBayesNet = incrementalHybrid.hybridBayesNet();
// // Check if we have a bayes net with 4 hybrid nodes, std::vector<std::pair<DiscreteValues, double>> assignments =
// // each with 2, 4, 5 (pruned), and 5 (pruned) leaves respetively. discreteConditional_m1.enumerate();
// EXPECT_LONGS_EQUAL(4, hybridBayesNet.size()); // Loop over all assignments and check the pruned components
// EXPECT_LONGS_EQUAL(2, hybridBayesNet.atGaussian(0)->nrComponents()); for (auto &&av : assignments) {
// EXPECT_LONGS_EQUAL(4, hybridBayesNet.atGaussian(1)->nrComponents()); const DiscreteValues &assignment = av.first;
// EXPECT_LONGS_EQUAL(5, hybridBayesNet.atGaussian(2)->nrComponents()); const double value = av.second;
// EXPECT_LONGS_EQUAL(5, hybridBayesNet.atGaussian(3)->nrComponents());
// // Check that the hybrid nodes of the bayes net match those of the bayes if (value == 0.0) {
// net EXPECT(lastDensity(assignment) == nullptr);
// // before pruning, at the same positions. } else {
// auto &lastDensity = *(hybridBayesNet.atGaussian(3)); CHECK(lastDensity(assignment));
// auto &unprunedLastDensity = *(unprunedHybridBayesNet->atGaussian(3)); EXPECT(assert_equal(*unprunedLastDensity(assignment),
// std::vector<std::pair<DiscreteValues, double>> assignments = *lastDensity(assignment)));
// discreteFactor_m1.enumerate(); }
// // Loop over all assignments and check the pruned components }
// for (auto &&av : assignments) {
// const DiscreteValues &assignment = av.first;
// const double value = av.second;
// if (value == 0.0) {
// EXPECT(lastDensity(assignment) == nullptr);
// } else {
// CHECK(lastDensity(assignment));
// EXPECT(assert_equal(*unprunedLastDensity(assignment),
// *lastDensity(assignment)));
// }
// }
} }
/* ****************************************************************************/ /* ****************************************************************************/
// Test approximate inference with an additional pruning step. // Test approximate inference with an additional pruning step.
TEST(HybridGaussianElimination, Incremental_approximate) { TEST(HybridGaussianElimination, Incremental_approximate) {
// Switching switching(5); Switching switching(5);
// IncrementalHybrid incrementalHybrid; HybridGaussianISAM incrementalHybrid;
// HybridGaussianFactorGraph graph1; HybridGaussianFactorGraph graph1;
// // Add the 3 DC factors, x1-x2, x2-x3, x3-x4 /***** Run Round 1 *****/
// for (size_t i = 0; i < 3; i++) { // Add the 3 hybrid factors, x1-x2, x2-x3, x3-x4
// graph1.push_back(switching.linearizedFactorGraph.dcGraph().at(i)); for (size_t i = 1; i < 4; i++) {
// } graph1.push_back(switching.linearizedFactorGraph.at(i));
}
// // Add the Gaussian factors, 1 prior on X(1), 4 measurements // Add the Gaussian factors, 1 prior on X(1),
// for (size_t i = 0; i <= 4; i++) { // 3 measurements on X(2), X(3), X(4)
// graph1.push_back(switching.linearizedFactorGraph.gaussianGraph().at(i)); graph1.push_back(switching.linearizedFactorGraph.at(0));
// } for (size_t i = 5; i <= 7; i++) {
graph1.push_back(switching.linearizedFactorGraph.at(i));
}
// // Create ordering. // Create ordering.
// Ordering ordering; Ordering ordering;
// for (size_t j = 1; j <= 4; j++) { for (size_t j = 1; j <= 4; j++) {
// ordering += X(j); ordering += X(j);
// } }
// // Run update with pruning // Run update with pruning
// size_t maxComponents = 5; size_t maxComponents = 5;
// incrementalHybrid.update(graph1, ordering, maxComponents); incrementalHybrid.update(graph1);
incrementalHybrid.prune(M(3), maxComponents);
// // Check if we have a bayes net with 4 hybrid nodes, // Check if we have a bayes tree with 4 hybrid nodes,
// // each with 2, 4, 8, and 5 (pruned) leaves respetively. // each with 2, 4, 8, and 5 (pruned) leaves respetively.
// auto actualBayesNet1 = incrementalHybrid.hybridBayesNet(); EXPECT_LONGS_EQUAL(4, incrementalHybrid.size());
// CHECK_EQUAL(4, actualBayesNet1.size()); EXPECT_LONGS_EQUAL(
// EXPECT_LONGS_EQUAL(2, actualBayesNet1.atGaussian(0)->nrComponents()); 2, incrementalHybrid[X(1)]->conditional()->asMixture()->nrComponents());
// EXPECT_LONGS_EQUAL(4, actualBayesNet1.atGaussian(1)->nrComponents()); EXPECT_LONGS_EQUAL(
// EXPECT_LONGS_EQUAL(8, actualBayesNet1.atGaussian(2)->nrComponents()); 4, incrementalHybrid[X(2)]->conditional()->asMixture()->nrComponents());
// EXPECT_LONGS_EQUAL(5, actualBayesNet1.atGaussian(3)->nrComponents()); EXPECT_LONGS_EQUAL(
5, incrementalHybrid[X(3)]->conditional()->asMixture()->nrComponents());
EXPECT_LONGS_EQUAL(
5, incrementalHybrid[X(4)]->conditional()->asMixture()->nrComponents());
// /***** Run Round 2 *****/ /***** Run Round 2 *****/
// HybridGaussianFactorGraph graph2; HybridGaussianFactorGraph graph2;
// graph2.push_back(switching.linearizedFactorGraph.dcGraph().at(3)); graph2.push_back(switching.linearizedFactorGraph.at(4));
// graph2.push_back(switching.linearizedFactorGraph.gaussianGraph().at(5)); graph2.push_back(switching.linearizedFactorGraph.at(8));
// Ordering ordering2; Ordering ordering2;
// ordering2 += X(4); ordering2 += X(4);
// ordering2 += X(5); ordering2 += X(5);
// // Run update with pruning a second time. // Run update with pruning a second time.
// incrementalHybrid.update(graph2, ordering2, maxComponents); incrementalHybrid.update(graph2);
incrementalHybrid.prune(M(4), maxComponents);
// // Check if we have a bayes net with 2 hybrid nodes, // Check if we have a bayes tree with pruned hybrid nodes,
// // each with 10 (pruned), and 5 (pruned) leaves respetively. // with 5 (pruned) leaves.
// auto actualBayesNet = incrementalHybrid.hybridBayesNet(); CHECK_EQUAL(5, incrementalHybrid.size());
// CHECK_EQUAL(2, actualBayesNet.size()); EXPECT_LONGS_EQUAL(
// EXPECT_LONGS_EQUAL(10, actualBayesNet.atGaussian(0)->nrComponents()); 5, incrementalHybrid[X(4)]->conditional()->asMixture()->nrComponents());
// EXPECT_LONGS_EQUAL(5, actualBayesNet.atGaussian(1)->nrComponents()); EXPECT_LONGS_EQUAL(
5, incrementalHybrid[X(5)]->conditional()->asMixture()->nrComponents());
} }
/* ************************************************************************/ /* ************************************************************************/
// Test for figuring out the optimal ordering to ensure we get // Test for figuring out the optimal ordering to ensure we get
// a discrete graph after elimination. // a discrete graph after elimination.
TEST(IncrementalHybrid, NonTrivial) { TEST(HybridGaussianISAM, NonTrivial) {
// // This is a GTSAM-only test for running inference on a single legged // This is a GTSAM-only test for running inference on a single legged robot.
// robot. // The leg links are represented by the chain X-Y-Z-W, where X is the base and
// // The leg links are represented by the chain X-Y-Z-W, where X is the base // W is the foot.
// and // We use BetweenFactor<Pose2> as constraints between each of the poses.
// // W is the foot.
// // We use BetweenFactor<Pose2> as constraints between each of the poses.
// /*************** Run Round 1 ***************/ /*************** Run Round 1 ***************/
// NonlinearHybridFactorGraph fg; HybridNonlinearFactorGraph fg;
// // Add a prior on pose x1 at the origin. // // Add a prior on pose x1 at the origin.
// // A prior factor consists of a mean and // // A prior factor consists of a mean and
// // a noise model (covariance matrix) // // a noise model (covariance matrix)
// Pose2 prior(0.0, 0.0, 0.0); // prior mean is at origin // Pose2 prior(0.0, 0.0, 0.0); // prior mean is at origin
// auto priorNoise = noiseModel::Diagonal::Sigmas( // auto priorNoise = noiseModel::Diagonal::Sigmas(
// Vector3(0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta // Vector3(0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta
// fg.emplace_nonlinear<PriorFactor<Pose2>>(X(0), prior, priorNoise); // fg.emplace_nonlinear<PriorFactor<Pose2>>(X(0), prior, priorNoise);
// // create a noise model for the landmark measurements // // create a noise model for the landmark measurements
// auto poseNoise = noiseModel::Isotropic::Sigma(3, 0.1); // auto poseNoise = noiseModel::Isotropic::Sigma(3, 0.1);
// // We model a robot's single leg as X - Y - Z - W // // We model a robot's single leg as X - Y - Z - W
// // where X is the base link and W is the foot link. // // where X is the base link and W is the foot link.
// // Add connecting poses similar to PoseFactors in GTD // // Add connecting poses similar to PoseFactors in GTD
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(0), Y(0), Pose2(0, 1.0, 0), // fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(0), Y(0), Pose2(0, 1.0, 0),
// poseNoise); // poseNoise);
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(Y(0), Z(0), Pose2(0, 1.0, 0), // fg.emplace_nonlinear<BetweenFactor<Pose2>>(Y(0), Z(0), Pose2(0, 1.0, 0),
// poseNoise); // poseNoise);
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(Z(0), W(0), Pose2(0, 1.0, 0), // fg.emplace_nonlinear<BetweenFactor<Pose2>>(Z(0), W(0), Pose2(0, 1.0, 0),
// poseNoise); // poseNoise);
// // Create initial estimate // // Create initial estimate
// Values initial; // Values initial;
// initial.insert(X(0), Pose2(0.0, 0.0, 0.0)); // initial.insert(X(0), Pose2(0.0, 0.0, 0.0));
// initial.insert(Y(0), Pose2(0.0, 1.0, 0.0)); // initial.insert(Y(0), Pose2(0.0, 1.0, 0.0));
// initial.insert(Z(0), Pose2(0.0, 2.0, 0.0)); // initial.insert(Z(0), Pose2(0.0, 2.0, 0.0));
// initial.insert(W(0), Pose2(0.0, 3.0, 0.0)); // initial.insert(W(0), Pose2(0.0, 3.0, 0.0));
// HybridGaussianFactorGraph gfg = fg.linearize(initial); // HybridGaussianFactorGraph gfg = fg.linearize(initial);
// fg = NonlinearHybridFactorGraph(); // fg = HybridNonlinearFactorGraph();
// IncrementalHybrid inc; // HybridGaussianISAM inc;
// // Regular ordering going up the chain. // // Regular ordering going up the chain.
// Ordering ordering; // Ordering ordering;
// ordering += W(0); // ordering += W(0);
// ordering += Z(0); // ordering += Z(0);
// ordering += Y(0); // ordering += Y(0);
// ordering += X(0); // ordering += X(0);
// // Update without pruning // // Update without pruning
// // The result is a HybridBayesNet with no discrete variables // // The result is a HybridBayesNet with no discrete variables
// // (equivalent to a GaussianBayesNet). // // (equivalent to a GaussianBayesNet).
// // Factorization is: // // Factorization is:
// // `P(X | measurements) = P(W0|Z0) P(Z0|Y0) P(Y0|X0) P(X0)` // // `P(X | measurements) = P(W0|Z0) P(Z0|Y0) P(Y0|X0) P(X0)`
// inc.update(gfg, ordering); // inc.update(gfg, ordering);
// /*************** Run Round 2 ***************/ // /*************** Run Round 2 ***************/
// using PlanarMotionModel = BetweenFactor<Pose2>; // using PlanarMotionModel = BetweenFactor<Pose2>;
// // Add odometry factor with discrete modes. // // Add odometry factor with discrete modes.
// Pose2 odometry(1.0, 0.0, 0.0); // Pose2 odometry(1.0, 0.0, 0.0);
// KeyVector contKeys = {W(0), W(1)}; // KeyVector contKeys = {W(0), W(1)};
// auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0); // auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
// auto still = boost::make_shared<PlanarMotionModel>(W(0), W(1), Pose2(0, 0, // auto still = boost::make_shared<PlanarMotionModel>(W(0), W(1), Pose2(0,
// 0), // 0, 0),
// noise_model), // noise_model),
// moving = boost::make_shared<PlanarMotionModel>(W(0), W(1), odometry, // moving = boost::make_shared<PlanarMotionModel>(W(0), W(1), odometry,
// noise_model); // noise_model);
// std::vector<PlanarMotionModel::shared_ptr> components = {moving, still}; // std::vector<PlanarMotionModel::shared_ptr> components = {moving, still};
// auto dcFactor = boost::make_shared<DCMixtureFactor<PlanarMotionModel>>( // auto dcFactor = boost::make_shared<DCMixtureFactor<PlanarMotionModel>>(
// contKeys, DiscreteKeys{gtsam::DiscreteKey(M(1), 2)}, components); // contKeys, DiscreteKeys{gtsam::DiscreteKey(M(1), 2)}, components);
// fg.push_back(dcFactor); // fg.push_back(dcFactor);
// // Add equivalent of ImuFactor // // Add equivalent of ImuFactor
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(0), X(1), Pose2(1.0, 0.0, 0), // fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(0), X(1), Pose2(1.0, 0.0,
// poseNoise); // 0),
// // PoseFactors-like at k=1 // poseNoise);
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(1), Y(1), Pose2(0, 1, 0), // // PoseFactors-like at k=1
// poseNoise); // fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(1), Y(1), Pose2(0, 1, 0),
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(Y(1), Z(1), Pose2(0, 1, 0), // poseNoise);
// poseNoise); // fg.emplace_nonlinear<BetweenFactor<Pose2>>(Y(1), Z(1), Pose2(0, 1, 0),
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(Z(1), W(1), Pose2(-1, 1, 0), // poseNoise);
// poseNoise); // fg.emplace_nonlinear<BetweenFactor<Pose2>>(Z(1), W(1), Pose2(-1, 1, 0),
// poseNoise);
// initial.insert(X(1), Pose2(1.0, 0.0, 0.0)); // initial.insert(X(1), Pose2(1.0, 0.0, 0.0));
// initial.insert(Y(1), Pose2(1.0, 1.0, 0.0)); // initial.insert(Y(1), Pose2(1.0, 1.0, 0.0));
// initial.insert(Z(1), Pose2(1.0, 2.0, 0.0)); // initial.insert(Z(1), Pose2(1.0, 2.0, 0.0));
// // The leg link did not move so we set the expected pose accordingly. // // The leg link did not move so we set the expected pose accordingly.
// initial.insert(W(1), Pose2(0.0, 3.0, 0.0)); // initial.insert(W(1), Pose2(0.0, 3.0, 0.0));
// // Ordering for k=1. // // Ordering for k=1.
// // This ordering follows the intuition that we eliminate the previous // // This ordering follows the intuition that we eliminate the previous
// // timestep, and then the current timestep. // // timestep, and then the current timestep.
// ordering = Ordering(); // ordering = Ordering();
// ordering += W(0); // ordering += W(0);
// ordering += Z(0); // ordering += Z(0);
// ordering += Y(0); // ordering += Y(0);
// ordering += X(0); // ordering += X(0);
// ordering += W(1); // ordering += W(1);
// ordering += Z(1); // ordering += Z(1);
// ordering += Y(1); // ordering += Y(1);
// ordering += X(1); // ordering += X(1);
// gfg = fg.linearize(initial); // gfg = fg.linearize(initial);
// fg = NonlinearHybridFactorGraph(); // fg = HybridNonlinearFactorGraph();
// // Update without pruning // // Update without pruning
// // The result is a HybridBayesNet with 1 discrete variable M(1). // // The result is a HybridBayesNet with 1 discrete variable M(1).
// // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1, M1) // // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1,
// // P(X0 | X1, W1, M1) P(W1|Z1, X1, M1) P(Z1|Y1, X1, // M1)
// M1) // // P(X0 | X1, W1, M1) P(W1|Z1, X1, M1) P(Z1|Y1, X1,
// // P(Y1 | X1, M1)P(X1 | M1)P(M1) // M1)
// // The MHS tree is a 2 level tree for time indices (0, 1) with 2 leaves. // // P(Y1 | X1, M1)P(X1 | M1)P(M1)
// inc.update(gfg, ordering); // // The MHS tree is a 2 level tree for time indices (0, 1) with 2 leaves.
// inc.update(gfg, ordering);
// /*************** Run Round 3 ***************/ // /*************** Run Round 3 ***************/
// // Add odometry factor with discrete modes. // // Add odometry factor with discrete modes.
// contKeys = {W(1), W(2)}; // contKeys = {W(1), W(2)};
// still = boost::make_shared<PlanarMotionModel>(W(1), W(2), Pose2(0, 0, 0), // still = boost::make_shared<PlanarMotionModel>(W(1), W(2), Pose2(0, 0, 0),
// noise_model); // noise_model);
// moving = // moving =
// boost::make_shared<PlanarMotionModel>(W(1), W(2), odometry, // boost::make_shared<PlanarMotionModel>(W(1), W(2), odometry,
// noise_model); // noise_model);
// components = {moving, still}; // components = {moving, still};
// dcFactor = boost::make_shared<DCMixtureFactor<PlanarMotionModel>>( // dcFactor = boost::make_shared<DCMixtureFactor<PlanarMotionModel>>(
// contKeys, DiscreteKeys{gtsam::DiscreteKey(M(2), 2)}, components); // contKeys, DiscreteKeys{gtsam::DiscreteKey(M(2), 2)}, components);
// fg.push_back(dcFactor); // fg.push_back(dcFactor);
// // Add equivalent of ImuFactor // // Add equivalent of ImuFactor
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(1), X(2), Pose2(1.0, 0.0, 0), // fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(1), X(2), Pose2(1.0, 0.0,
// poseNoise); // 0),
// // PoseFactors-like at k=1 // poseNoise);
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(2), Y(2), Pose2(0, 1, 0), // // PoseFactors-like at k=1
// poseNoise); // fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(2), Y(2), Pose2(0, 1, 0),
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(Y(2), Z(2), Pose2(0, 1, 0), // poseNoise);
// poseNoise); // fg.emplace_nonlinear<BetweenFactor<Pose2>>(Y(2), Z(2), Pose2(0, 1, 0),
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(Z(2), W(2), Pose2(-2, 1, 0), // poseNoise);
// poseNoise); // fg.emplace_nonlinear<BetweenFactor<Pose2>>(Z(2), W(2), Pose2(-2, 1, 0),
// poseNoise);
// initial.insert(X(2), Pose2(2.0, 0.0, 0.0)); // initial.insert(X(2), Pose2(2.0, 0.0, 0.0));
// initial.insert(Y(2), Pose2(2.0, 1.0, 0.0)); // initial.insert(Y(2), Pose2(2.0, 1.0, 0.0));
// initial.insert(Z(2), Pose2(2.0, 2.0, 0.0)); // initial.insert(Z(2), Pose2(2.0, 2.0, 0.0));
// initial.insert(W(2), Pose2(0.0, 3.0, 0.0)); // initial.insert(W(2), Pose2(0.0, 3.0, 0.0));
// // Ordering at k=2. Same intuition as before. // // Ordering at k=2. Same intuition as before.
// ordering = Ordering(); // ordering = Ordering();
// ordering += W(1); // ordering += W(1);
// ordering += Z(1); // ordering += Z(1);
// ordering += Y(1); // ordering += Y(1);
// ordering += X(1); // ordering += X(1);
// ordering += W(2); // ordering += W(2);
// ordering += Z(2); // ordering += Z(2);
// ordering += Y(2); // ordering += Y(2);
// ordering += X(2); // ordering += X(2);
// gfg = fg.linearize(initial); // gfg = fg.linearize(initial);
// fg = NonlinearHybridFactorGraph(); // fg = HybridNonlinearFactorGraph();
// // Now we prune! // // Now we prune!
// // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1, M1) // // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1,
// P(X0 | X1, W1, M1) // M1) P(X0 | X1, W1, M1)
// // P(W1|W2, Z1, X1, M1, M2) P(Z1| W2, Y1, X1, M1, M2) // // P(W1|W2, Z1, X1, M1, M2) P(Z1| W2, Y1, X1, M1,
// P(Y1 | W2, X1, M1, M2) // M2) P(Y1 | W2, X1, M1, M2)
// // P(X1 | W2, X2, M1, M2) P(W2|Z2, X2, M1, M2) // // P(X1 | W2, X2, M1, M2) P(W2|Z2, X2, M1, M2)
// P(Z2|Y2, X2, M1, M2) // P(Z2|Y2, X2, M1, M2)
// // P(Y2 | X2, M1, M2)P(X2 | M1, M2) P(M1, M2) // // P(Y2 | X2, M1, M2)P(X2 | M1, M2) P(M1, M2)
// // The MHS at this point should be a 3 level tree on (0, 1, 2). // // The MHS at this point should be a 3 level tree on (0, 1, 2).
// // 0 has 2 choices, 1 has 4 choices and 2 has 4 choices. // // 0 has 2 choices, 1 has 4 choices and 2 has 4 choices.
// inc.update(gfg, ordering, 2); // inc.update(gfg, ordering, 2);
// /*************** Run Round 4 ***************/ // /*************** Run Round 4 ***************/
// // Add odometry factor with discrete modes. // // Add odometry factor with discrete modes.
// contKeys = {W(2), W(3)}; // contKeys = {W(2), W(3)};
// still = boost::make_shared<PlanarMotionModel>(W(2), W(3), Pose2(0, 0, 0), // still = boost::make_shared<PlanarMotionModel>(W(2), W(3), Pose2(0, 0, 0),
// noise_model); // noise_model);
// moving = // moving =
// boost::make_shared<PlanarMotionModel>(W(2), W(3), odometry, // boost::make_shared<PlanarMotionModel>(W(2), W(3), odometry,
// noise_model); // noise_model);
// components = {moving, still}; // components = {moving, still};
// dcFactor = boost::make_shared<DCMixtureFactor<PlanarMotionModel>>( // dcFactor = boost::make_shared<DCMixtureFactor<PlanarMotionModel>>(
// contKeys, DiscreteKeys{gtsam::DiscreteKey(M(3), 2)}, components); // contKeys, DiscreteKeys{gtsam::DiscreteKey(M(3), 2)}, components);
// fg.push_back(dcFactor); // fg.push_back(dcFactor);
// // Add equivalent of ImuFactor // // Add equivalent of ImuFactor
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(2), X(3), Pose2(1.0, 0.0, 0), // fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(2), X(3), Pose2(1.0, 0.0,
// poseNoise); // 0),
// // PoseFactors-like at k=3 // poseNoise);
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(3), Y(3), Pose2(0, 1, 0), // // PoseFactors-like at k=3
// poseNoise); // fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(3), Y(3), Pose2(0, 1, 0),
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(Y(3), Z(3), Pose2(0, 1, 0), // poseNoise);
// poseNoise); // fg.emplace_nonlinear<BetweenFactor<Pose2>>(Y(3), Z(3), Pose2(0, 1, 0),
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(Z(3), W(3), Pose2(-3, 1, 0), // poseNoise);
// poseNoise); // fg.emplace_nonlinear<BetweenFactor<Pose2>>(Z(3), W(3), Pose2(-3, 1, 0),
// poseNoise);
// initial.insert(X(3), Pose2(3.0, 0.0, 0.0)); // initial.insert(X(3), Pose2(3.0, 0.0, 0.0));
// initial.insert(Y(3), Pose2(3.0, 1.0, 0.0)); // initial.insert(Y(3), Pose2(3.0, 1.0, 0.0));
// initial.insert(Z(3), Pose2(3.0, 2.0, 0.0)); // initial.insert(Z(3), Pose2(3.0, 2.0, 0.0));
// initial.insert(W(3), Pose2(0.0, 3.0, 0.0)); // initial.insert(W(3), Pose2(0.0, 3.0, 0.0));
// // Ordering at k=3. Same intuition as before. // // Ordering at k=3. Same intuition as before.
// ordering = Ordering(); // ordering = Ordering();
// ordering += W(2); // ordering += W(2);
// ordering += Z(2); // ordering += Z(2);
// ordering += Y(2); // ordering += Y(2);
// ordering += X(2); // ordering += X(2);
// ordering += W(3); // ordering += W(3);
// ordering += Z(3); // ordering += Z(3);
// ordering += Y(3); // ordering += Y(3);
// ordering += X(3); // ordering += X(3);
// gfg = fg.linearize(initial); // gfg = fg.linearize(initial);
// fg = NonlinearHybridFactorGraph(); // fg = HybridNonlinearFactorGraph();
// // Keep pruning! // // Keep pruning!
// inc.update(gfg, ordering, 3); // inc.update(gfg, ordering, 3);
// // The final discrete graph should not be empty since we have eliminated // // The final discrete graph should not be empty since we have eliminated
// // all continuous variables. // // all continuous variables.
// EXPECT(!inc.remainingDiscreteGraph().empty()); // EXPECT(!inc.remainingDiscreteGraph().empty());
// // Test if the optimal discrete mode assignment is (1, 1, 1). // // Test if the optimal discrete mode assignment is (1, 1, 1).
// DiscreteValues optimal_assignment = // DiscreteValues optimal_assignment =
// inc.remainingDiscreteGraph().optimize(); DiscreteValues // inc.remainingDiscreteGraph().optimize(); DiscreteValues
// expected_assignment; expected_assignment[M(1)] = 1; // expected_assignment; expected_assignment[M(1)] = 1;
// expected_assignment[M(2)] = 1; // expected_assignment[M(2)] = 1;
// expected_assignment[M(3)] = 1; // expected_assignment[M(3)] = 1;
// EXPECT(assert_equal(expected_assignment, optimal_assignment)); // EXPECT(assert_equal(expected_assignment, optimal_assignment));
// // Test if pruning worked correctly by checking that we only have 3 leaves // // Test if pruning worked correctly by checking that we only have 3
// in // leaves in
// // the last node. // // the last node.
// auto lastConditional = boost::dynamic_pointer_cast<GaussianMixture>( // auto lastConditional = boost::dynamic_pointer_cast<GaussianMixture>(
// inc.hybridBayesNet().at(inc.hybridBayesNet().size() - 1)); // inc.hybridBayesNet().at(inc.hybridBayesNet().size() - 1));
// EXPECT_LONGS_EQUAL(3, lastConditional->nrComponents()); // EXPECT_LONGS_EQUAL(3, lastConditional->nrComponents());
} }
/* ************************************************************************* */ /* ************************************************************************* */