testGaussianDensity.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 
20 #include <gtsam/inference/Symbol.h>
21 
23 
24 using namespace gtsam;
25 using namespace std;
27 
28 /* ************************************************************************* */
30 {
31  Matrix R = (Matrix(2,2) <<
32  -12.1244, -5.1962,
33  0., 4.6904).finished();
34 
35  Vector d = Vector2(1.0, 2.0), s = Vector2(3.0, 4.0);
37 
38  GaussianDensity copied(conditional);
39  EXPECT(assert_equal(d, copied.d()));
40  EXPECT(assert_equal(s, copied.get_model()->sigmas()));
41 }
42 
43 /* ************************************************************************* */
44 // Test FromMeanAndStddev named constructor
45 TEST(GaussianDensity, FromMeanAndStddev) {
46  Matrix A1 = (Matrix(2, 2) << 1., 2., 3., 4.).finished();
47  const Vector2 b(20, 40), x0(1, 2);
48  const double sigma = 3;
49 
51  values.insert(X(0), x0);
52 
54  Vector2 e = (x0 - b) / sigma;
55  double expected1 = 0.5 * e.dot(e);
56  EXPECT_DOUBLES_EQUAL(expected1, density.error(values), 1e-9);
57 
58  double expected2 = -(density.negLogConstant() + 0.5 * e.dot(e));
59  EXPECT_DOUBLES_EQUAL(expected2, density.logProbability(values), 1e-9);
60 }
61 
62 /* ************************************************************************* */
63 int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
64 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Vector2
Eigen::Vector2d Vector2
Definition: Vector.h:42
TestHarness.h
gtsam::JacobianFactor::get_model
const SharedDiagonal & get_model() const
Definition: JacobianFactor.h:292
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
gtsam::noiseModel::Diagonal::Sigmas
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:291
X
#define X
Definition: icosphere.cpp:20
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
sampling::sigma
static const double sigma
Definition: testGaussianBayesNet.cpp:170
gtsam::symbol_shorthand::X
Key X(std::uint64_t j)
Definition: inference/Symbol.h:171
gtsam::VectorValues
Definition: VectorValues.h:74
main
int main()
Definition: testGaussianDensity.cpp:63
gtsam::GaussianConditional
Definition: GaussianConditional.h:40
x0
static Symbol x0('x', 0)
density
Definition: testGaussianConditional.cpp:127
gtsam::GaussianConditional::d
const constBVector d() const
Definition: GaussianConditional.h:231
Symbol.h
GaussianDensity.h
A Gaussian Density.
gtsam::HybridValues::insert
void insert(Key j, const Vector &value)
Definition: HybridValues.cpp:85
Vector2
Definition: test_operator_overloading.cpp:18
gtsam::GaussianDensity
Definition: GaussianDensity.h:32
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
TestResult
Definition: TestResult.h:26
gtsam::b
const G & b
Definition: Group.h:79
gtsam
traits
Definition: SFMdata.h:40
gtsam::TEST
TEST(SmartFactorBase, Pinhole)
Definition: testSmartFactorBase.cpp:38
constructor
Definition: init.h:200
std
Definition: BFloat16.h:88
A1
static const double A1[]
Definition: expn.h:6
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
R
Rot2 R(Rot2::fromAngle(0.1))
gtsam::GaussianDensity::FromMeanAndStddev
static GaussianDensity FromMeanAndStddev(Key key, const Vector &mean, double sigma)
Construct using a mean and standard deviation.
Definition: GaussianDensity.cpp:29


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:07:27