testGaussianMixture.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 
25 #include <gtsam/inference/Symbol.h>
27 
28 #include <vector>
29 
30 // Include for test suite
32 
33 using namespace gtsam;
38 
39 // Common constants
40 static const Key modeKey = M(0);
41 static const DiscreteKey mode(modeKey, 2);
42 static const VectorValues vv{{Z(0), Vector1(4.9)}, {X(0), Vector1(5.0)}};
43 static const DiscreteValues assignment0{{M(0), 0}}, assignment1{{M(0), 1}};
44 static const HybridValues hv0{vv, assignment0};
45 static const HybridValues hv1{vv, assignment1};
46 
47 /* ************************************************************************* */
48 namespace equal_constants {
49 // Create a simple GaussianMixture
50 const double commonSigma = 2.0;
51 const std::vector<GaussianConditional::shared_ptr> conditionals{
53  commonSigma),
55  commonSigma)};
56 const GaussianMixture mixture({Z(0)}, {X(0)}, {mode}, conditionals);
57 } // namespace equal_constants
58 
59 /* ************************************************************************* */
61 TEST(GaussianMixture, Invariants) {
62  using namespace equal_constants;
63 
64  // Check that the mixture normalization constant is the max of all constants
65  // which are all equal, in this case, hence:
66  const double K = mixture.logNormalizationConstant();
67  EXPECT_DOUBLES_EQUAL(K, conditionals[0]->logNormalizationConstant(), 1e-8);
68  EXPECT_DOUBLES_EQUAL(K, conditionals[1]->logNormalizationConstant(), 1e-8);
69 
72 }
73 
74 /* ************************************************************************* */
76 TEST(GaussianMixture, LogProbability) {
77  using namespace equal_constants;
78  auto actual = mixture.logProbability(vv);
79 
80  // Check result.
81  std::vector<DiscreteKey> discrete_keys = {mode};
82  std::vector<double> leaves = {conditionals[0]->logProbability(vv),
83  conditionals[1]->logProbability(vv)};
84  AlgebraicDecisionTree<Key> expected(discrete_keys, leaves);
85 
86  EXPECT(assert_equal(expected, actual, 1e-6));
87 
88  // Check for non-tree version.
89  for (size_t mode : {0, 1}) {
90  const HybridValues hv{vv, {{M(0), mode}}};
91  EXPECT_DOUBLES_EQUAL(conditionals[mode]->logProbability(vv),
92  mixture.logProbability(hv), 1e-8);
93  }
94 }
95 
96 /* ************************************************************************* */
99  using namespace equal_constants;
100  auto actual = mixture.errorTree(vv);
101 
102  // Check result.
103  std::vector<DiscreteKey> discrete_keys = {mode};
104  std::vector<double> leaves = {conditionals[0]->error(vv),
105  conditionals[1]->error(vv)};
106  AlgebraicDecisionTree<Key> expected(discrete_keys, leaves);
107 
108  EXPECT(assert_equal(expected, actual, 1e-6));
109 
110  // Check for non-tree version.
111  for (size_t mode : {0, 1}) {
112  const HybridValues hv{vv, {{M(0), mode}}};
114  1e-8);
115  }
116 }
117 
118 /* ************************************************************************* */
121 TEST(GaussianMixture, Likelihood) {
122  using namespace equal_constants;
123 
124  // Compute likelihood
125  auto likelihood = mixture.likelihood(vv);
126 
127  // Check that the mixture error and the likelihood error are the same.
128  EXPECT_DOUBLES_EQUAL(mixture.error(hv0), likelihood->error(hv0), 1e-8);
129  EXPECT_DOUBLES_EQUAL(mixture.error(hv1), likelihood->error(hv1), 1e-8);
130 
131  // Check that likelihood error is as expected, i.e., just the errors of the
132  // individual likelihoods, in the `equal_constants` case.
133  std::vector<DiscreteKey> discrete_keys = {mode};
134  std::vector<double> leaves = {conditionals[0]->likelihood(vv)->error(vv),
135  conditionals[1]->likelihood(vv)->error(vv)};
136  AlgebraicDecisionTree<Key> expected(discrete_keys, leaves);
137  EXPECT(assert_equal(expected, likelihood->errorTree(vv), 1e-6));
138 
139  // Check that the ratio of probPrime to evaluate is the same for all modes.
140  std::vector<double> ratio(2);
141  for (size_t mode : {0, 1}) {
142  const HybridValues hv{vv, {{M(0), mode}}};
143  ratio[mode] = std::exp(-likelihood->error(hv)) / mixture.evaluate(hv);
144  }
145  EXPECT_DOUBLES_EQUAL(ratio[0], ratio[1], 1e-8);
146 }
147 
148 /* ************************************************************************* */
150 // Create a GaussianMixture with mode-dependent noise models.
151 // 0 is low-noise, 1 is high-noise.
152 const std::vector<GaussianConditional::shared_ptr> conditionals{
154  0.5),
156  3.0)};
157 const GaussianMixture mixture({Z(0)}, {X(0)}, {mode}, conditionals);
158 } // namespace mode_dependent_constants
159 
160 /* ************************************************************************* */
161 // Create a test for continuousParents.
162 TEST(GaussianMixture, ContinuousParents) {
163  using namespace mode_dependent_constants;
164  const KeyVector continuousParentKeys = mixture.continuousParents();
165  // Check that the continuous parent keys are correct:
166  EXPECT(continuousParentKeys.size() == 1);
167  EXPECT(continuousParentKeys[0] == X(0));
168 }
169 
170 /* ************************************************************************* */
173 TEST(GaussianMixture, Likelihood2) {
174  using namespace mode_dependent_constants;
175 
176  // Compute likelihood
177  auto likelihood = mixture.likelihood(vv);
178 
179  // Check that the mixture error and the likelihood error are as expected,
180  // this invariant is the same as the equal noise case:
181  EXPECT_DOUBLES_EQUAL(mixture.error(hv0), likelihood->error(hv0), 1e-8);
182  EXPECT_DOUBLES_EQUAL(mixture.error(hv1), likelihood->error(hv1), 1e-8);
183 
184  // Check the detailed JacobianFactor calculation for mode==1.
185  {
186  // We have a JacobianFactor
187  const auto gf1 = (*likelihood)(assignment1);
188  const auto jf1 = std::dynamic_pointer_cast<JacobianFactor>(gf1);
189  CHECK(jf1);
190 
191  // It has 2 rows, not 1!
192  CHECK(jf1->rows() == 2);
193 
194  // Check that the constant C1 is properly encoded in the JacobianFactor.
195  const double C1 = mixture.logNormalizationConstant() -
196  conditionals[1]->logNormalizationConstant();
197  const double c1 = std::sqrt(2.0 * C1);
198  Vector expected_unwhitened(2);
199  expected_unwhitened << 4.9 - 5.0, -c1;
200  Vector actual_unwhitened = jf1->unweighted_error(vv);
201  EXPECT(assert_equal(expected_unwhitened, actual_unwhitened));
202 
203  // Make sure the noise model does not touch it.
204  Vector expected_whitened(2);
205  expected_whitened << (4.9 - 5.0) / 3.0, -c1;
206  Vector actual_whitened = jf1->error_vector(vv);
207  EXPECT(assert_equal(expected_whitened, actual_whitened));
208 
209  // Check that the error is equal to the mixture error:
210  EXPECT_DOUBLES_EQUAL(mixture.error(hv1), jf1->error(hv1), 1e-8);
211  }
212 
213  // Check that the ratio of probPrime to evaluate is the same for all modes.
214  std::vector<double> ratio(2);
215  for (size_t mode : {0, 1}) {
216  const HybridValues hv{vv, {{M(0), mode}}};
217  ratio[mode] = std::exp(-likelihood->error(hv)) / mixture.evaluate(hv);
218  }
219  EXPECT_DOUBLES_EQUAL(ratio[0], ratio[1], 1e-8);
220 }
221 
222 /* ************************************************************************* */
223 int main() {
224  TestResult tr;
225  return TestRegistry::runAllTests(tr);
226 }
227 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::Vector1
Eigen::Matrix< double, 1, 1 > Vector1
Definition: Vector.h:41
gtsam::HybridValues
Definition: HybridValues.h:38
GaussianConditional.h
Conditional Gaussian Base class.
equal_constants::commonSigma
const double commonSigma
Definition: testGaussianMixture.cpp:50
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
gtsam::symbol_shorthand::M
Key M(std::uint64_t j)
Definition: inference/Symbol.h:160
gtsam::GaussianMixture
A conditional of gaussian mixtures indexed by discrete variables, as part of a Bayes Network....
Definition: GaussianMixture.h:53
gtsam::GaussianMixture::logNormalizationConstant
double logNormalizationConstant() const override
Definition: GaussianMixture.h:161
X
#define X
Definition: icosphere.cpp:20
exp
const EIGEN_DEVICE_FUNC ExpReturnType exp() const
Definition: ArrayCwiseUnaryOps.h:97
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::GaussianMixture::continuousParents
KeyVector continuousParents() const
Returns the continuous keys among the parents.
Definition: GaussianMixture.cpp:162
gtsam::AlgebraicDecisionTree< Key >
c1
static double c1
Definition: airy.c:54
gtsam::symbol_shorthand::X
Key X(std::uint64_t j)
Definition: inference/Symbol.h:171
vv
static const VectorValues vv
Definition: testGaussianMixture.cpp:42
mode_dependent_constants
Definition: testGaussianMixture.cpp:149
gtsam::VectorValues
Definition: VectorValues.h:74
gtsam::noiseModel::Isotropic
Definition: NoiseModel.h:527
assignment0
static const DiscreteValues assignment0
Definition: testGaussianMixture.cpp:43
gtsam::symbol_shorthand::Z
Key Z(std::uint64_t j)
Definition: inference/Symbol.h:173
C1
Definition: test_operator_overloading.cpp:97
modeKey
static const Key modeKey
Definition: testGaussianMixture.cpp:40
gtsam::Conditional< HybridFactor, GaussianMixture >::CheckInvariants
static bool CheckInvariants(const GaussianMixture &conditional, const VALUES &x)
Definition: Conditional-inst.h:77
gtsam::GaussianMixture::likelihood
std::shared_ptr< GaussianMixtureFactor > likelihood(const VectorValues &given) const
Definition: GaussianMixture.cpp:188
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
assignment1
static const DiscreteValues assignment1
Definition: testGaussianMixture.cpp:43
GaussianMixture.h
A hybrid conditional in the Conditional Linear Gaussian scheme.
main
int main()
Definition: testGaussianMixture.cpp:223
Symbol.h
gtsam::GaussianMixture::logProbability
AlgebraicDecisionTree< Key > logProbability(const VectorValues &continuousValues) const
Compute logProbability of the GaussianMixture as a tree.
Definition: GaussianMixture.cpp:298
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
TestResult
Definition: TestResult.h:26
hv1
static const HybridValues hv1
Definition: testGaussianMixture.cpp:45
hv0
static const HybridValues hv0
Definition: testGaussianMixture.cpp:44
gtsam::GaussianMixture::errorTree
AlgebraicDecisionTree< Key > errorTree(const VectorValues &continuousValues) const
Compute error of the GaussianMixture as a tree.
Definition: GaussianMixture.cpp:316
gtsam
traits
Definition: chartTesting.h:28
gtsam::TEST
TEST(SmartFactorBase, Pinhole)
Definition: testSmartFactorBase.cpp:38
DiscreteValues.h
error
static double error
Definition: testRot3.cpp:37
K
#define K
Definition: igam.h:8
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
CHECK
#define CHECK(condition)
Definition: Test.h:108
gtsam::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
equal_constants
Definition: testGaussianMixture.cpp:48
ratio
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size ratio
Definition: gnuplot_common_settings.hh:44
mode_dependent_constants::conditionals
const std::vector< GaussianConditional::shared_ptr > conditionals
Definition: testGaussianMixture.cpp:152
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
mode_dependent_constants::mixture
const GaussianMixture mixture({Z(0)}, {X(0)}, {mode}, conditionals)
mode
static const DiscreteKey mode(modeKey, 2)
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
Z
#define Z
Definition: icosphere.cpp:21
gtsam::GaussianMixture::evaluate
double evaluate(const HybridValues &values) const override
Calculate probability density for given values.
Definition: GaussianMixture.cpp:341
HybridValues.h
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
GaussianMixtureFactor.h
A set of GaussianFactors, indexed by a set of discrete keys.
gtsam::GaussianConditional::sharedMeanAndStddev
static shared_ptr sharedMeanAndStddev(Args &&... args)
Create shared pointer by forwarding arguments to fromMeanAndStddev.
Definition: GaussianConditional.h:105
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51
gtsam::GaussianMixture::error
double error(const HybridValues &values) const override
Compute the error of this Gaussian Mixture.
Definition: GaussianMixture.cpp:327


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:05:50