testDiscreteSearch.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
12 /*
13  * testDiscreteSearch.cpp
14  *
15  * @date January, 2025
16  * @author Frank Dellaert
17  */
18 
20 #include <gtsam/base/Testable.h>
22 
23 #include "AsiaExample.h"
24 
25 using namespace gtsam;
26 
27 // Create Asia Bayes net, FG, and Bayes tree once
28 namespace asia {
29 using namespace asia_example;
31 
32 // Create factor graph and optimize with max-product for MPE
35 
36 // Create ordering
37 static const Ordering ordering{D, X, B, E, L, T, S, A};
38 
39 // Create Bayes tree
42 } // namespace asia
43 
44 /* ************************************************************************* */
45 TEST(DiscreteBayesNet, EmptyKBest) {
46  DiscreteBayesNet net; // no factors
47  DiscreteSearch search(net);
48  auto solutions = search.run(3);
49  // Expect one solution with empty assignment, error=0
50  EXPECT_LONGS_EQUAL(1, solutions.size());
51  EXPECT_DOUBLES_EQUAL(0, std::fabs(solutions[0].error), 1e-9);
52 }
53 
54 /* ************************************************************************* */
55 TEST(DiscreteBayesTree, EmptyTree) {
57 
58  DiscreteSearch search(bt);
59  auto solutions = search.run(3);
60 
61  // We expect exactly 1 solution with error = 0.0 (the empty assignment).
62  EXPECT_LONGS_EQUAL(1, solutions.size());
63  EXPECT_DOUBLES_EQUAL(0, std::fabs(solutions[0].error), 1e-9);
64 }
65 
66 /* ************************************************************************* */
67 TEST(DiscreteBayesNet, AsiaKBest) {
68  auto fromETree =
70  auto fromJunctionTree =
72  const DiscreteSearch fromBayesNet(asia::bayesNet);
73  const DiscreteSearch fromBayesTree(asia::bayesTree);
74 
75  for (auto& search :
76  {fromETree, fromJunctionTree, fromBayesNet, fromBayesTree}) {
77  // Ask for the MPE
78  auto mpe = search.run();
79 
80  // Regression on error lower bound
81  EXPECT_DOUBLES_EQUAL(1.205536, search.lowerBound(), 1e-5);
82 
83  // Check that the cost-to-go heuristic decreases from there
84  auto slots = search.slots();
85  double previousHeuristic = search.lowerBound();
86  for (auto&& slot : slots) {
87  EXPECT(slot.heuristic <= previousHeuristic);
88  previousHeuristic = slot.heuristic;
89  }
90 
91  EXPECT_LONGS_EQUAL(1, mpe.size());
92  // Regression test: check the MPE solution
93  EXPECT_DOUBLES_EQUAL(1.236627, std::fabs(mpe[0].error), 1e-5);
94 
95  // Check it is equal to MPE via inference
96  EXPECT(assert_equal(asia::mpe, mpe[0].assignment));
97 
98  // Ask for top 4 solutions
99  auto solutions = search.run(4);
100 
101  EXPECT_LONGS_EQUAL(4, solutions.size());
102  // Regression test: check the first and last solution
103  EXPECT_DOUBLES_EQUAL(1.236627, std::fabs(solutions[0].error), 1e-5);
104  EXPECT_DOUBLES_EQUAL(2.201708, std::fabs(solutions[3].error), 1e-5);
105  }
106 }
107 
108 /* ************************************************************************* */
109 int main() {
110  TestResult tr;
111  return TestRegistry::runAllTests(tr);
112 }
113 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
B
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Definition: bench_gemm.cpp:49
asia::bayesNet
static const DiscreteBayesNet bayesNet
Definition: testDiscreteSearch.cpp:30
D
MatrixXcd D
Definition: EigenSolver_EigenSolver_MatrixType.cpp:14
gtsam::DiscreteFactorGraph
Definition: DiscreteFactorGraph.h:99
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
Testable.h
Concept check for values that can be used in unit tests.
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
main
int main()
Definition: testDiscreteSearch.cpp:109
gtsam::DiscreteSearch::run
std::vector< Solution > run(size_t K=1) const
Search for the K best solutions.
Definition: DiscreteSearch.cpp:226
gtsam::DiscreteSearch
DiscreteSearch: Search for the K best solutions.
Definition: DiscreteSearch.h:44
asia::bayesTree
static const DiscreteBayesTree bayesTree
Definition: testDiscreteSearch.cpp:40
T
Eigen::Triplet< double > T
Definition: Tutorial_sparse_example.cpp:6
X
#define X
Definition: icosphere.cpp:20
AsiaExample.h
gtsam::DiscreteSearch::FromFactorGraph
static DiscreteSearch FromFactorGraph(const DiscreteFactorGraph &factorGraph, const Ordering &ordering, bool buildJunctionTree=false)
Definition: DiscreteSearch.cpp:179
asia::factorGraph
static const DiscreteFactorGraph factorGraph(bayesNet)
gtsam::EliminateableFactorGraph::eliminateMultifrontal
std::shared_ptr< BayesTreeType > eliminateMultifrontal(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
Definition: EliminateableFactorGraph-inst.h:89
asia::ordering
static const Ordering ordering
Definition: testDiscreteSearch.cpp:37
A
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
boost::multiprecision::fabs
Real fabs(const Real &a)
Definition: boostmultiprec.cpp:119
net
gtsam::DiscreteBayesNet
Definition: DiscreteBayesNet.h:38
L
MatrixXd L
Definition: LLT_example.cpp:6
asia::mpe
static const DiscreteValues mpe
Definition: testDiscreteSearch.cpp:34
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
ordering
static enum @1096 ordering
TestResult
Definition: TestResult.h:26
E
DiscreteKey E(5, 2)
gtsam::asia_example::createAsiaExample
DiscreteBayesNet createAsiaExample()
Definition: AsiaExample.h:52
gtsam
traits
Definition: SFMdata.h:40
gtsam::TEST
TEST(SmartFactorBase, Pinhole)
Definition: testSmartFactorBase.cpp:38
asia
Definition: testDiscreteSearch.cpp:28
error
static double error
Definition: testRot3.cpp:37
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
DiscreteSearch.h
Defines the DiscreteSearch class for discrete search algorithms.
gtsam::DiscreteBayesTree
A Bayes tree representing a Discrete distribution.
Definition: DiscreteBayesTree.h:73
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
gtsam::DiscreteFactorGraph::optimize
DiscreteValues optimize(OptionalOrderingType orderingType={}) const
Find the maximum probable explanation (MPE) by doing max-product.
Definition: DiscreteFactorGraph.cpp:187
gtsam::Ordering
Definition: inference/Ordering.h:33
S
DiscreteKey S(1, 2)


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:06:33