File: testSimulated2DOriented.cpp

package info (click to toggle)
gtsam 4.2.0%2Bdfsg-3
  • links: PTS, VCS
  • area: main
  • in suites: forky, sid
  • size: 46,108 kB
  • sloc: cpp: 127,191; python: 14,312; xml: 8,442; makefile: 252; sh: 119; ansic: 101
file content (72 lines) | stat: -rw-r--r-- 2,373 bytes parent folder | download | duplicates (2)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
/* ----------------------------------------------------------------------------

 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
 * Atlanta, Georgia 30332-0415
 * All Rights Reserved
 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)

 * See LICENSE for the license information

 * -------------------------------------------------------------------------- */

/**
 * @file testSimulated2DOriented.cpp
 * @date Jun 10, 2010
 * @author nikai
 * @brief unit tests for simulated2DOriented
 */

#include <tests/simulated2D.h>
#include <tests/simulated2DOriented.h>
#include <gtsam/inference/Symbol.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/numericalDerivative.h>

using namespace std;
using namespace gtsam;

#include <iostream>
#include <CppUnitLite/TestHarness.h>

// Convenience for named keys
using symbol_shorthand::X;
using symbol_shorthand::L;

/* ************************************************************************* */
TEST( simulated2DOriented, Dprior )
{
  Pose2 x(1,-9, 0.1);
  Matrix numerical = numericalDerivative11(simulated2DOriented::prior,x);
  Matrix computed;
  simulated2DOriented::prior(x,computed);
  CHECK(assert_equal(numerical,computed,1e-9));
}

/* ************************************************************************* */
  TEST( simulated2DOriented, DOdo )
{
  Pose2 x1(1,-9,0.1),x2(-5,6,0.2);
  Matrix H1,H2;
  simulated2DOriented::odo(x1,x2,H1,H2);
  Matrix A1 = numericalDerivative21(simulated2DOriented::odo,x1,x2);
  CHECK(assert_equal(A1,H1,1e-9));
  Matrix A2 = numericalDerivative22(simulated2DOriented::odo,x1,x2);
  CHECK(assert_equal(A2,H2,1e-9));
}

/* ************************************************************************* */
TEST( simulated2DOriented, constructor )
{
  Pose2 measurement(0.2, 0.3, 0.1);
  SharedDiagonal model = noiseModel::Diagonal::Sigmas(Vector3(1., 1., 1.));
  simulated2DOriented::Odometry factor(measurement, model, X(1), X(2));

  simulated2DOriented::Values config;
  config.insert(X(1), Pose2(1., 0., 0.2));
  config.insert(X(2), Pose2(2., 0., 0.1));
  boost::shared_ptr<GaussianFactor> lf = factor.linearize(config);
}

/* ************************************************************************* */
int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
/* ************************************************************************* */