|
|
|
|
@ -54,7 +54,7 @@ TEST(HybridGaussianElimination, IncrementalElimination) {
|
|
|
|
|
// Create initial factor graph
|
|
|
|
|
// * * *
|
|
|
|
|
// | | |
|
|
|
|
|
// *- X1 -*- X2 -*- X3
|
|
|
|
|
// X1 -*- X2 -*- X3
|
|
|
|
|
// \*-M1-*/
|
|
|
|
|
graph1.push_back(switching.linearizedFactorGraph.at(0)); // P(X1)
|
|
|
|
|
graph1.push_back(switching.linearizedFactorGraph.at(1)); // P(X1, X2 | M1)
|
|
|
|
|
@ -179,7 +179,8 @@ TEST(HybridGaussianElimination, IncrementalInference) {
|
|
|
|
|
|
|
|
|
|
DiscreteValues m00;
|
|
|
|
|
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);
|
|
|
|
|
|
|
|
|
|
auto discreteConditional = isam[M(2)]->conditional()->asDiscreteConditional();
|
|
|
|
|
@ -200,8 +201,8 @@ TEST(HybridGaussianElimination, IncrementalInference) {
|
|
|
|
|
assignment[M(2)] = 1;
|
|
|
|
|
EXPECT(assert_equal(0.2, (*discreteConditional)(assignment), 1e-5));
|
|
|
|
|
|
|
|
|
|
// Check if the clique conditional generated from incremental elimination matches
|
|
|
|
|
// that of batch elimination.
|
|
|
|
|
// Check if the clique conditional generated from incremental elimination
|
|
|
|
|
// matches that of batch elimination.
|
|
|
|
|
auto expectedChordal = expectedRemainingGraph->eliminateMultifrontal();
|
|
|
|
|
auto expectedConditional = dynamic_pointer_cast<DecisionTreeFactor>(
|
|
|
|
|
(*expectedChordal)[M(2)]->conditional()->inner());
|
|
|
|
|
@ -213,192 +214,184 @@ TEST(HybridGaussianElimination, IncrementalInference) {
|
|
|
|
|
/* ****************************************************************************/
|
|
|
|
|
// Test if we can approximately do the inference
|
|
|
|
|
TEST(HybridGaussianElimination, Approx_inference) {
|
|
|
|
|
// Switching switching(4);
|
|
|
|
|
// IncrementalHybrid incrementalHybrid;
|
|
|
|
|
// HybridGaussianFactorGraph graph1;
|
|
|
|
|
Switching switching(4);
|
|
|
|
|
HybridGaussianISAM incrementalHybrid;
|
|
|
|
|
HybridGaussianFactorGraph graph1;
|
|
|
|
|
|
|
|
|
|
// // Add the 3 DC factors, x1-x2, x2-x3, x3-x4
|
|
|
|
|
// for (size_t i = 0; i < 3; i++) {
|
|
|
|
|
// graph1.push_back(switching.linearizedFactorGraph.dcGraph().at(i));
|
|
|
|
|
// }
|
|
|
|
|
// Add the 3 hybrid factors, x1-x2, x2-x3, x3-x4
|
|
|
|
|
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
|
|
|
|
|
// for (size_t i = 0; i <= 4; i++) {
|
|
|
|
|
// graph1.push_back(switching.linearizedFactorGraph.gaussianGraph().at(i));
|
|
|
|
|
// }
|
|
|
|
|
// Add the Gaussian factors, 1 prior on X(1),
|
|
|
|
|
// 3 measurements on X(2), X(3), X(4)
|
|
|
|
|
graph1.push_back(switching.linearizedFactorGraph.at(0));
|
|
|
|
|
for (size_t i = 4; i <= 7; i++) {
|
|
|
|
|
graph1.push_back(switching.linearizedFactorGraph.at(i));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// // Create ordering.
|
|
|
|
|
// Ordering ordering;
|
|
|
|
|
// for (size_t j = 1; j <= 4; j++) {
|
|
|
|
|
// ordering += X(j);
|
|
|
|
|
// }
|
|
|
|
|
// Create ordering.
|
|
|
|
|
Ordering ordering;
|
|
|
|
|
for (size_t j = 1; j <= 4; j++) {
|
|
|
|
|
ordering += X(j);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// // Now we calculate the actual factors using full elimination
|
|
|
|
|
// HybridBayesNet::shared_ptr unprunedHybridBayesNet;
|
|
|
|
|
// HybridGaussianFactorGraph::shared_ptr unprunedRemainingGraph;
|
|
|
|
|
// std::tie(unprunedHybridBayesNet, unprunedRemainingGraph) =
|
|
|
|
|
// switching.linearizedFactorGraph.eliminatePartialSequential(ordering);
|
|
|
|
|
// Now we calculate the actual factors using full elimination
|
|
|
|
|
HybridBayesTree::shared_ptr unprunedHybridBayesTree;
|
|
|
|
|
HybridGaussianFactorGraph::shared_ptr unprunedRemainingGraph;
|
|
|
|
|
std::tie(unprunedHybridBayesTree, unprunedRemainingGraph) =
|
|
|
|
|
switching.linearizedFactorGraph.eliminatePartialMultifrontal(ordering);
|
|
|
|
|
|
|
|
|
|
// size_t maxComponents = 5;
|
|
|
|
|
// incrementalHybrid.update(graph1, ordering, maxComponents);
|
|
|
|
|
size_t maxNrLeaves = 5;
|
|
|
|
|
incrementalHybrid.update(graph1);
|
|
|
|
|
|
|
|
|
|
// /*
|
|
|
|
|
// 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 *
|
|
|
|
|
incrementalHybrid.prune(M(3), maxNrLeaves);
|
|
|
|
|
|
|
|
|
|
// pruned factors is:
|
|
|
|
|
// Choice(m3)
|
|
|
|
|
// 0 Choice(m2)
|
|
|
|
|
// 0 0 Leaf 0
|
|
|
|
|
// 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
|
|
|
|
|
// 1 0 1 Leaf 0.6124
|
|
|
|
|
// 1 1 Choice(m1)
|
|
|
|
|
// 1 1 0 Leaf 0.611
|
|
|
|
|
// 1 1 1 Leaf 1
|
|
|
|
|
// */
|
|
|
|
|
/*
|
|
|
|
|
unpruned factor is:
|
|
|
|
|
Choice(m3)
|
|
|
|
|
0 Choice(m2)
|
|
|
|
|
0 0 Choice(m1)
|
|
|
|
|
0 0 0 Leaf 0.11267528
|
|
|
|
|
0 0 1 Leaf 0.18576102
|
|
|
|
|
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.18576102
|
|
|
|
|
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
|
|
|
|
|
// // DecisionTreeFactor on {M3, M2, M1}.
|
|
|
|
|
// auto remainingFactorGraph = incrementalHybrid.remainingFactorGraph();
|
|
|
|
|
// EXPECT_LONGS_EQUAL(1, remainingFactorGraph.size());
|
|
|
|
|
pruned factors is:
|
|
|
|
|
Choice(m3)
|
|
|
|
|
0 Choice(m2)
|
|
|
|
|
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>(
|
|
|
|
|
// incrementalHybrid.remainingDiscreteGraph().at(0));
|
|
|
|
|
// EXPECT(discreteFactor_m1.keys() == KeyVector({M(3), M(2), M(1)}));
|
|
|
|
|
auto discreteConditional_m1 = *dynamic_pointer_cast<DiscreteConditional>(
|
|
|
|
|
incrementalHybrid[M(1)]->conditional()->inner());
|
|
|
|
|
EXPECT(discreteConditional_m1.keys() == KeyVector({M(1), M(2), M(3)}));
|
|
|
|
|
|
|
|
|
|
// // Get the number of elements which are equal to 0.
|
|
|
|
|
// auto count = [](const double &value, int count) {
|
|
|
|
|
// return value > 0 ? count + 1 : count;
|
|
|
|
|
// };
|
|
|
|
|
// // Check that the number of leaves after pruning is 5.
|
|
|
|
|
// EXPECT_LONGS_EQUAL(5, discreteFactor_m1.fold(count, 0));
|
|
|
|
|
// Get the number of elements which are greater than 0.
|
|
|
|
|
auto count = [](const double &value, int count) {
|
|
|
|
|
return value > 0 ? count + 1 : count;
|
|
|
|
|
};
|
|
|
|
|
// Check that the number of leaves after pruning is 5.
|
|
|
|
|
EXPECT_LONGS_EQUAL(5, discreteConditional_m1.fold(count, 0));
|
|
|
|
|
|
|
|
|
|
// /* Expected hybrid Bayes net
|
|
|
|
|
// * factor 0: [x1 | x2 m1 ], 2 components
|
|
|
|
|
// * factor 1: [x2 | x3 m2 m1 ], 4 components
|
|
|
|
|
// * factor 2: [x3 | x4 m3 m2 m1 ], 8 components
|
|
|
|
|
// * factor 3: [x4 | m3 m2 m1 ], 8 components
|
|
|
|
|
// */
|
|
|
|
|
// auto hybridBayesNet = incrementalHybrid.hybridBayesNet();
|
|
|
|
|
// Check that the hybrid nodes of the bayes net match those of the pre-pruning
|
|
|
|
|
// bayes net, at the same positions.
|
|
|
|
|
auto &unprunedLastDensity = *dynamic_pointer_cast<GaussianMixture>(
|
|
|
|
|
unprunedHybridBayesTree->clique(X(4))->conditional()->inner());
|
|
|
|
|
auto &lastDensity = *dynamic_pointer_cast<GaussianMixture>(
|
|
|
|
|
incrementalHybrid[X(4)]->conditional()->inner());
|
|
|
|
|
|
|
|
|
|
// // Check if we have a bayes net with 4 hybrid nodes,
|
|
|
|
|
// // each with 2, 4, 5 (pruned), and 5 (pruned) leaves respetively.
|
|
|
|
|
// EXPECT_LONGS_EQUAL(4, hybridBayesNet.size());
|
|
|
|
|
// EXPECT_LONGS_EQUAL(2, hybridBayesNet.atGaussian(0)->nrComponents());
|
|
|
|
|
// EXPECT_LONGS_EQUAL(4, hybridBayesNet.atGaussian(1)->nrComponents());
|
|
|
|
|
// EXPECT_LONGS_EQUAL(5, hybridBayesNet.atGaussian(2)->nrComponents());
|
|
|
|
|
// EXPECT_LONGS_EQUAL(5, hybridBayesNet.atGaussian(3)->nrComponents());
|
|
|
|
|
std::vector<std::pair<DiscreteValues, double>> assignments =
|
|
|
|
|
discreteConditional_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;
|
|
|
|
|
|
|
|
|
|
// // Check that the hybrid nodes of the bayes net match those of the bayes
|
|
|
|
|
// net
|
|
|
|
|
// // before pruning, at the same positions.
|
|
|
|
|
// auto &lastDensity = *(hybridBayesNet.atGaussian(3));
|
|
|
|
|
// auto &unprunedLastDensity = *(unprunedHybridBayesNet->atGaussian(3));
|
|
|
|
|
// std::vector<std::pair<DiscreteValues, double>> assignments =
|
|
|
|
|
// 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)));
|
|
|
|
|
// }
|
|
|
|
|
// }
|
|
|
|
|
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(HybridGaussianElimination, Incremental_approximate) {
|
|
|
|
|
// Switching switching(5);
|
|
|
|
|
// IncrementalHybrid incrementalHybrid;
|
|
|
|
|
// HybridGaussianFactorGraph graph1;
|
|
|
|
|
Switching switching(5);
|
|
|
|
|
HybridGaussianISAM incrementalHybrid;
|
|
|
|
|
HybridGaussianFactorGraph graph1;
|
|
|
|
|
|
|
|
|
|
// // Add the 3 DC factors, x1-x2, x2-x3, x3-x4
|
|
|
|
|
// for (size_t i = 0; i < 3; i++) {
|
|
|
|
|
// graph1.push_back(switching.linearizedFactorGraph.dcGraph().at(i));
|
|
|
|
|
// }
|
|
|
|
|
/***** Run Round 1 *****/
|
|
|
|
|
// Add the 3 hybrid factors, x1-x2, x2-x3, x3-x4
|
|
|
|
|
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
|
|
|
|
|
// for (size_t i = 0; i <= 4; i++) {
|
|
|
|
|
// graph1.push_back(switching.linearizedFactorGraph.gaussianGraph().at(i));
|
|
|
|
|
// }
|
|
|
|
|
// Add the Gaussian factors, 1 prior on X(1),
|
|
|
|
|
// 3 measurements on X(2), X(3), X(4)
|
|
|
|
|
graph1.push_back(switching.linearizedFactorGraph.at(0));
|
|
|
|
|
for (size_t i = 5; i <= 7; i++) {
|
|
|
|
|
graph1.push_back(switching.linearizedFactorGraph.at(i));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// // Create ordering.
|
|
|
|
|
// Ordering ordering;
|
|
|
|
|
// for (size_t j = 1; j <= 4; j++) {
|
|
|
|
|
// ordering += X(j);
|
|
|
|
|
// }
|
|
|
|
|
// Create ordering.
|
|
|
|
|
Ordering ordering;
|
|
|
|
|
for (size_t j = 1; j <= 4; j++) {
|
|
|
|
|
ordering += X(j);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// // Run update with pruning
|
|
|
|
|
// size_t maxComponents = 5;
|
|
|
|
|
// incrementalHybrid.update(graph1, ordering, maxComponents);
|
|
|
|
|
// Run update with pruning
|
|
|
|
|
size_t maxComponents = 5;
|
|
|
|
|
incrementalHybrid.update(graph1);
|
|
|
|
|
incrementalHybrid.prune(M(3), maxComponents);
|
|
|
|
|
|
|
|
|
|
// // Check if we have a bayes net with 4 hybrid nodes,
|
|
|
|
|
// // each with 2, 4, 8, and 5 (pruned) leaves respetively.
|
|
|
|
|
// auto actualBayesNet1 = incrementalHybrid.hybridBayesNet();
|
|
|
|
|
// CHECK_EQUAL(4, actualBayesNet1.size());
|
|
|
|
|
// EXPECT_LONGS_EQUAL(2, actualBayesNet1.atGaussian(0)->nrComponents());
|
|
|
|
|
// EXPECT_LONGS_EQUAL(4, actualBayesNet1.atGaussian(1)->nrComponents());
|
|
|
|
|
// EXPECT_LONGS_EQUAL(8, actualBayesNet1.atGaussian(2)->nrComponents());
|
|
|
|
|
// EXPECT_LONGS_EQUAL(5, actualBayesNet1.atGaussian(3)->nrComponents());
|
|
|
|
|
// Check if we have a bayes tree with 4 hybrid nodes,
|
|
|
|
|
// each with 2, 4, 8, and 5 (pruned) leaves respetively.
|
|
|
|
|
EXPECT_LONGS_EQUAL(4, incrementalHybrid.size());
|
|
|
|
|
EXPECT_LONGS_EQUAL(
|
|
|
|
|
2, incrementalHybrid[X(1)]->conditional()->asMixture()->nrComponents());
|
|
|
|
|
EXPECT_LONGS_EQUAL(
|
|
|
|
|
4, incrementalHybrid[X(2)]->conditional()->asMixture()->nrComponents());
|
|
|
|
|
EXPECT_LONGS_EQUAL(
|
|
|
|
|
5, incrementalHybrid[X(3)]->conditional()->asMixture()->nrComponents());
|
|
|
|
|
EXPECT_LONGS_EQUAL(
|
|
|
|
|
5, incrementalHybrid[X(4)]->conditional()->asMixture()->nrComponents());
|
|
|
|
|
|
|
|
|
|
// /***** Run Round 2 *****/
|
|
|
|
|
// HybridGaussianFactorGraph graph2;
|
|
|
|
|
// graph2.push_back(switching.linearizedFactorGraph.dcGraph().at(3));
|
|
|
|
|
// graph2.push_back(switching.linearizedFactorGraph.gaussianGraph().at(5));
|
|
|
|
|
/***** Run Round 2 *****/
|
|
|
|
|
HybridGaussianFactorGraph graph2;
|
|
|
|
|
graph2.push_back(switching.linearizedFactorGraph.at(4));
|
|
|
|
|
graph2.push_back(switching.linearizedFactorGraph.at(8));
|
|
|
|
|
|
|
|
|
|
// Ordering ordering2;
|
|
|
|
|
// ordering2 += X(4);
|
|
|
|
|
// ordering2 += X(5);
|
|
|
|
|
Ordering ordering2;
|
|
|
|
|
ordering2 += X(4);
|
|
|
|
|
ordering2 += X(5);
|
|
|
|
|
|
|
|
|
|
// // Run update with pruning a second time.
|
|
|
|
|
// incrementalHybrid.update(graph2, ordering2, maxComponents);
|
|
|
|
|
// Run update with pruning a second time.
|
|
|
|
|
incrementalHybrid.update(graph2);
|
|
|
|
|
incrementalHybrid.prune(M(4), maxComponents);
|
|
|
|
|
|
|
|
|
|
// // Check if we have a bayes net with 2 hybrid nodes,
|
|
|
|
|
// // each with 10 (pruned), and 5 (pruned) leaves respetively.
|
|
|
|
|
// auto actualBayesNet = incrementalHybrid.hybridBayesNet();
|
|
|
|
|
// CHECK_EQUAL(2, actualBayesNet.size());
|
|
|
|
|
// EXPECT_LONGS_EQUAL(10, actualBayesNet.atGaussian(0)->nrComponents());
|
|
|
|
|
// EXPECT_LONGS_EQUAL(5, actualBayesNet.atGaussian(1)->nrComponents());
|
|
|
|
|
// Check if we have a bayes tree with pruned hybrid nodes,
|
|
|
|
|
// with 5 (pruned) leaves.
|
|
|
|
|
CHECK_EQUAL(5, incrementalHybrid.size());
|
|
|
|
|
EXPECT_LONGS_EQUAL(
|
|
|
|
|
5, incrementalHybrid[X(4)]->conditional()->asMixture()->nrComponents());
|
|
|
|
|
EXPECT_LONGS_EQUAL(
|
|
|
|
|
5, incrementalHybrid[X(5)]->conditional()->asMixture()->nrComponents());
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/* ************************************************************************/
|
|
|
|
|
// Test for figuring out the optimal ordering to ensure we get
|
|
|
|
|
// a discrete graph after elimination.
|
|
|
|
|
TEST(IncrementalHybrid, NonTrivial) {
|
|
|
|
|
// // This is a GTSAM-only test for running inference on a single legged
|
|
|
|
|
// robot.
|
|
|
|
|
// // The leg links are represented by the chain X-Y-Z-W, where X is the base
|
|
|
|
|
// and
|
|
|
|
|
// // W is the foot.
|
|
|
|
|
// // We use BetweenFactor<Pose2> as constraints between each of the poses.
|
|
|
|
|
TEST(HybridGaussianISAM, NonTrivial) {
|
|
|
|
|
// This is a GTSAM-only test for running inference on a single legged robot.
|
|
|
|
|
// The leg links are represented by the chain X-Y-Z-W, where X is the base and
|
|
|
|
|
// W is the foot.
|
|
|
|
|
// We use BetweenFactor<Pose2> as constraints between each of the poses.
|
|
|
|
|
|
|
|
|
|
// /*************** Run Round 1 ***************/
|
|
|
|
|
// NonlinearHybridFactorGraph fg;
|
|
|
|
|
/*************** Run Round 1 ***************/
|
|
|
|
|
HybridNonlinearFactorGraph fg;
|
|
|
|
|
|
|
|
|
|
// // Add a prior on pose x1 at the origin.
|
|
|
|
|
// // A prior factor consists of a mean and
|
|
|
|
|
@ -430,9 +423,9 @@ TEST(IncrementalHybrid, NonTrivial) {
|
|
|
|
|
// initial.insert(W(0), Pose2(0.0, 3.0, 0.0));
|
|
|
|
|
|
|
|
|
|
// HybridGaussianFactorGraph gfg = fg.linearize(initial);
|
|
|
|
|
// fg = NonlinearHybridFactorGraph();
|
|
|
|
|
// fg = HybridNonlinearFactorGraph();
|
|
|
|
|
|
|
|
|
|
// IncrementalHybrid inc;
|
|
|
|
|
// HybridGaussianISAM inc;
|
|
|
|
|
|
|
|
|
|
// // Regular ordering going up the chain.
|
|
|
|
|
// Ordering ordering;
|
|
|
|
|
@ -455,8 +448,8 @@ TEST(IncrementalHybrid, NonTrivial) {
|
|
|
|
|
// Pose2 odometry(1.0, 0.0, 0.0);
|
|
|
|
|
// KeyVector contKeys = {W(0), W(1)};
|
|
|
|
|
// auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
|
|
|
|
|
// auto still = boost::make_shared<PlanarMotionModel>(W(0), W(1), Pose2(0, 0,
|
|
|
|
|
// 0),
|
|
|
|
|
// auto still = boost::make_shared<PlanarMotionModel>(W(0), W(1), Pose2(0,
|
|
|
|
|
// 0, 0),
|
|
|
|
|
// noise_model),
|
|
|
|
|
// moving = boost::make_shared<PlanarMotionModel>(W(0), W(1), odometry,
|
|
|
|
|
// noise_model);
|
|
|
|
|
@ -466,7 +459,8 @@ TEST(IncrementalHybrid, NonTrivial) {
|
|
|
|
|
// fg.push_back(dcFactor);
|
|
|
|
|
|
|
|
|
|
// // 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,
|
|
|
|
|
// 0),
|
|
|
|
|
// poseNoise);
|
|
|
|
|
// // PoseFactors-like at k=1
|
|
|
|
|
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(1), Y(1), Pose2(0, 1, 0),
|
|
|
|
|
@ -496,11 +490,12 @@ TEST(IncrementalHybrid, NonTrivial) {
|
|
|
|
|
// ordering += X(1);
|
|
|
|
|
|
|
|
|
|
// gfg = fg.linearize(initial);
|
|
|
|
|
// fg = NonlinearHybridFactorGraph();
|
|
|
|
|
// fg = HybridNonlinearFactorGraph();
|
|
|
|
|
|
|
|
|
|
// // Update without pruning
|
|
|
|
|
// // 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,
|
|
|
|
|
// M1)
|
|
|
|
|
// // P(X0 | X1, W1, M1) P(W1|Z1, X1, M1) P(Z1|Y1, X1,
|
|
|
|
|
// M1)
|
|
|
|
|
// // P(Y1 | X1, M1)P(X1 | M1)P(M1)
|
|
|
|
|
@ -521,7 +516,8 @@ TEST(IncrementalHybrid, NonTrivial) {
|
|
|
|
|
// fg.push_back(dcFactor);
|
|
|
|
|
|
|
|
|
|
// // 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,
|
|
|
|
|
// 0),
|
|
|
|
|
// poseNoise);
|
|
|
|
|
// // PoseFactors-like at k=1
|
|
|
|
|
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(2), Y(2), Pose2(0, 1, 0),
|
|
|
|
|
@ -548,13 +544,13 @@ TEST(IncrementalHybrid, NonTrivial) {
|
|
|
|
|
// ordering += X(2);
|
|
|
|
|
|
|
|
|
|
// gfg = fg.linearize(initial);
|
|
|
|
|
// fg = NonlinearHybridFactorGraph();
|
|
|
|
|
// fg = HybridNonlinearFactorGraph();
|
|
|
|
|
|
|
|
|
|
// // Now we prune!
|
|
|
|
|
// // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1, M1)
|
|
|
|
|
// P(X0 | X1, W1, M1)
|
|
|
|
|
// // P(W1|W2, Z1, X1, M1, M2) P(Z1| W2, Y1, X1, M1, M2)
|
|
|
|
|
// P(Y1 | W2, X1, M1, M2)
|
|
|
|
|
// // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1,
|
|
|
|
|
// M1) P(X0 | X1, W1, M1)
|
|
|
|
|
// // P(W1|W2, Z1, X1, M1, M2) P(Z1| W2, Y1, X1, M1,
|
|
|
|
|
// M2) P(Y1 | W2, X1, M1, M2)
|
|
|
|
|
// // P(X1 | W2, X2, M1, M2) P(W2|Z2, X2, M1, M2)
|
|
|
|
|
// P(Z2|Y2, X2, M1, M2)
|
|
|
|
|
// // P(Y2 | X2, M1, M2)P(X2 | M1, M2) P(M1, M2)
|
|
|
|
|
@ -576,7 +572,8 @@ TEST(IncrementalHybrid, NonTrivial) {
|
|
|
|
|
// fg.push_back(dcFactor);
|
|
|
|
|
|
|
|
|
|
// // 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,
|
|
|
|
|
// 0),
|
|
|
|
|
// poseNoise);
|
|
|
|
|
// // PoseFactors-like at k=3
|
|
|
|
|
// fg.emplace_nonlinear<BetweenFactor<Pose2>>(X(3), Y(3), Pose2(0, 1, 0),
|
|
|
|
|
@ -603,7 +600,7 @@ TEST(IncrementalHybrid, NonTrivial) {
|
|
|
|
|
// ordering += X(3);
|
|
|
|
|
|
|
|
|
|
// gfg = fg.linearize(initial);
|
|
|
|
|
// fg = NonlinearHybridFactorGraph();
|
|
|
|
|
// fg = HybridNonlinearFactorGraph();
|
|
|
|
|
|
|
|
|
|
// // Keep pruning!
|
|
|
|
|
// inc.update(gfg, ordering, 3);
|
|
|
|
|
@ -620,8 +617,8 @@ TEST(IncrementalHybrid, NonTrivial) {
|
|
|
|
|
// expected_assignment[M(3)] = 1;
|
|
|
|
|
// EXPECT(assert_equal(expected_assignment, optimal_assignment));
|
|
|
|
|
|
|
|
|
|
// // Test if pruning worked correctly by checking that we only have 3 leaves
|
|
|
|
|
// in
|
|
|
|
|
// // Test if pruning worked correctly by checking that we only have 3
|
|
|
|
|
// leaves in
|
|
|
|
|
// // the last node.
|
|
|
|
|
// auto lastConditional = boost::dynamic_pointer_cast<GaussianMixture>(
|
|
|
|
|
// inc.hybridBayesNet().at(inc.hybridBayesNet().size() - 1));
|
|
|
|
|
|