testSimulated3D.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 
18 #include <tests/simulated3D.h>
19 #include <gtsam/inference/Symbol.h>
20 #include <gtsam/geometry/Pose3.h>
21 #include <gtsam/base/Testable.h>
23 
25 
26 #include <iostream>
27 
28 using namespace gtsam;
29 
30 // Convenience for named keys
33 
34 /* ************************************************************************* */
35 TEST( simulated3D, Values )
36 {
37  Values actual;
38  actual.insert(L(1),Point3(1,1,1));
39  actual.insert(X(2),Point3(2,2,2));
40  EXPECT(assert_equal(actual,actual,1e-9));
41 }
42 
43 /* ************************************************************************* */
44 TEST( simulated3D, Dprior )
45 {
46  Point3 x(1,-9, 7);
47  Matrix numerical = numericalDerivative11<Point3, Point3>(boost::bind(simulated3D::prior, _1, boost::none),x);
48  Matrix computed;
49  simulated3D::prior(x,computed);
50  EXPECT(assert_equal(numerical,computed,1e-9));
51 }
52 
53 /* ************************************************************************* */
54 TEST( simulated3D, DOdo )
55 {
56  Point3 x1(1,-9,7),x2(-5,6,7);
57  Matrix H1,H2;
58  simulated3D::odo(x1,x2,H1,H2);
59  Matrix A1 = numericalDerivative21<Point3, Point3, Point3>(boost::bind(simulated3D::odo, _1, _2, boost::none, boost::none),x1,x2);
60  EXPECT(assert_equal(A1,H1,1e-9));
61  Matrix A2 = numericalDerivative22<Point3, Point3, Point3>(boost::bind(simulated3D::odo, _1, _2, boost::none, boost::none),x1,x2);
62  EXPECT(assert_equal(A2,H2,1e-9));
63 }
64 
65 
66 /* ************************************************************************* */
67 int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
68 /* ************************************************************************* */
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Point3 odo(const Point3 &x1, const Point3 &x2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none)
Definition: simulated3D.h:49
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
MatrixXd L
Definition: LLT_example.cpp:6
Some functions to compute numerical derivatives.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Key X(std::uint64_t j)
int main()
#define EXPECT(condition)
Definition: Test.h:151
Array< double, 1, 3 > e(1./3., 0.5, 2.)
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Pose3 x1
Definition: testPose3.cpp:588
Key L(std::uint64_t j)
TEST(LPInitSolver, InfiniteLoopSingleVar)
Vector3 Point3
Definition: Point3.h:35
#define X
Definition: icosphere.cpp:20
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 x
3D Pose
Point3 prior(const Point3 &x, boost::optional< Matrix & > H=boost::none)
Definition: simulated3D.h:41


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:49:32