testMixtureFactor.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 
22 #include <gtsam/inference/Symbol.h>
24 
25 // Include for test suite
27 
28 using namespace std;
29 using namespace gtsam;
33 
34 /* ************************************************************************* */
35 // Check iterators of empty mixture.
36 TEST(MixtureFactor, Constructor) {
37  MixtureFactor factor;
38  MixtureFactor::const_iterator const_it = factor.begin();
39  CHECK(const_it == factor.end());
40  MixtureFactor::iterator it = factor.begin();
41  CHECK(it == factor.end());
42 }
43 
44 /* ************************************************************************* */
45 // Test .print() output.
46 TEST(MixtureFactor, Printing) {
47  DiscreteKey m1(1, 2);
48  double between0 = 0.0;
49  double between1 = 1.0;
50 
51  Vector1 sigmas = Vector1(1.0);
52  auto model = noiseModel::Diagonal::Sigmas(sigmas, false);
53 
54  auto f0 =
55  std::make_shared<BetweenFactor<double>>(X(1), X(2), between0, model);
56  auto f1 =
57  std::make_shared<BetweenFactor<double>>(X(1), X(2), between1, model);
58  std::vector<NonlinearFactor::shared_ptr> factors{f0, f1};
59 
60  MixtureFactor mixtureFactor({X(1), X(2)}, {m1}, factors);
61 
62  std::string expected =
63  R"(Hybrid [x1 x2; 1]
64 MixtureFactor
65  Choice(1)
66  0 Leaf Nonlinear factor on 2 keys
67  1 Leaf Nonlinear factor on 2 keys
68 )";
69  EXPECT(assert_print_equal(expected, mixtureFactor));
70 }
71 
72 /* ************************************************************************* */
74  DiscreteKey m1(1, 2);
75 
76  double between0 = 0.0;
77  double between1 = 1.0;
78 
79  Vector1 sigmas = Vector1(1.0);
80  auto model = noiseModel::Diagonal::Sigmas(sigmas, false);
81 
82  auto f0 =
83  std::make_shared<BetweenFactor<double>>(X(1), X(2), between0, model);
84  auto f1 =
85  std::make_shared<BetweenFactor<double>>(X(1), X(2), between1, model);
86  std::vector<NonlinearFactor::shared_ptr> factors{f0, f1};
87 
88  return MixtureFactor({X(1), X(2)}, {m1}, factors);
89 }
90 
91 /* ************************************************************************* */
92 // Test the error of the MixtureFactor
93 TEST(MixtureFactor, Error) {
94  auto mixtureFactor = getMixtureFactor();
95 
96  Values continuousValues;
97  continuousValues.insert<double>(X(1), 0);
98  continuousValues.insert<double>(X(2), 1);
99 
100  AlgebraicDecisionTree<Key> error_tree =
101  mixtureFactor.errorTree(continuousValues);
102 
103  DiscreteKey m1(1, 2);
104  std::vector<DiscreteKey> discrete_keys = {m1};
105  std::vector<double> errors = {0.5, 0};
106  AlgebraicDecisionTree<Key> expected_error(discrete_keys, errors);
107 
108  EXPECT(assert_equal(expected_error, error_tree));
109 }
110 
111 /* ************************************************************************* */
112 // Test dim of the MixtureFactor
113 TEST(MixtureFactor, Dim) {
114  auto mixtureFactor = getMixtureFactor();
115  EXPECT_LONGS_EQUAL(1, mixtureFactor.dim());
116 }
117 
118 /* ************************************************************************* */
119 int main() {
120  TestResult tr;
121  return TestRegistry::runAllTests(tr);
122 }
123 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
main
int main()
Definition: testMixtureFactor.cpp:114
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
gtsam::assert_print_equal
bool assert_print_equal(const std::string &expected, const V &actual, const std::string &s="")
Definition: TestableAssertions.h:352
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
m1
Matrix3d m1
Definition: IOFormat.cpp:2
X
#define X
Definition: icosphere.cpp:20
gtsam::Factor::begin
const_iterator begin() const
Definition: Factor.h:145
TestableAssertions.h
Provides additional testing facilities for common data structures.
gtsam::AlgebraicDecisionTree< Key >
Vector1
Eigen::Matrix< double, 1, 1 > Vector1
Definition: testEvent.cpp:33
BetweenFactor.h
gtsam::noiseModel::Isotropic
Definition: NoiseModel.h:527
exampleQR::sigmas
Vector sigmas
Definition: testNoiseModel.cpp:212
TEST
TEST(MixtureFactor, Constructor)
Definition: testMixtureFactor.cpp:36
getMixtureFactor
static MixtureFactor getMixtureFactor()
Definition: testMixtureFactor.cpp:68
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
Symbol.h
gtsam::Factor::end
const_iterator end() const
Definition: Factor.h:148
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
MixtureFactor.h
Nonlinear Mixture factor of continuous and discrete.
TestResult
Definition: TestResult.h:26
gtsam
traits
Definition: chartTesting.h:28
DiscreteValues.h
gtsam::Values
Definition: Values.h:65
CHECK
#define CHECK(condition)
Definition: Test.h:108
gtsam::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
std
Definition: BFloat16.h:88
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::MixtureFactor
Implementation of a discrete conditional mixture factor.
Definition: MixtureFactor.h:47
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
unary::f1
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
Definition: testExpression.cpp:79
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:06:15