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 std::placeholders;
29 using namespace gtsam;
30 
31 // Convenience for named keys
34 
35 /* ************************************************************************* */
36 TEST( simulated3D, Values )
37 {
38  Values actual;
39  actual.insert(L(1),Point3(1,1,1));
40  actual.insert(X(2),Point3(2,2,2));
41  EXPECT(assert_equal(actual,actual,1e-9));
42 }
43 
44 /* ************************************************************************* */
45 TEST( simulated3D, Dprior )
46 {
47  Point3 x(1,-9, 7);
48  Matrix numerical = numericalDerivative11<Point3, Point3>(std::bind(simulated3D::prior, std::placeholders::_1, nullptr),x);
49  Matrix computed;
50  simulated3D::prior(x,computed);
51  EXPECT(assert_equal(numerical,computed,1e-9));
52 }
53 
54 /* ************************************************************************* */
55 TEST( simulated3D, DOdo )
56 {
57  Point3 x1(1, -9, 7), x2(-5, 6, 7);
58  Matrix H1, H2;
59  simulated3D::odo(x1, x2, H1, H2);
60  Matrix A1 = numericalDerivative21<Point3, Point3, Point3>(
61  std::bind(simulated3D::odo, std::placeholders::_1, std::placeholders::_2,
62  nullptr, nullptr),
63  x1, x2);
64  EXPECT(assert_equal(A1, H1, 1e-9));
65  Matrix A2 = numericalDerivative22<Point3, Point3, Point3>(
66  std::bind(simulated3D::odo, std::placeholders::_1, std::placeholders::_2,
67  nullptr, nullptr),
68  x1, x2);
69  EXPECT(assert_equal(A2, H2, 1e-9));
70 }
71 
72 
73 /* ************************************************************************* */
74 int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
75 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
main
int main()
Definition: testSimulated3D.cpp:74
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Testable.h
Concept check for values that can be used in unit tests.
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
x
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
Definition: gnuplot_common_settings.hh:12
simulated3D.h
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
X
#define X
Definition: icosphere.cpp:20
TEST
TEST(simulated3D, Values)
Definition: testSimulated3D.cpp:36
numericalDerivative.h
Some functions to compute numerical derivatives.
x1
Pose3 x1
Definition: testPose3.cpp:663
A2
static const double A2[]
Definition: expn.h:7
L
MatrixXd L
Definition: LLT_example.cpp:6
Symbol.h
TestResult
Definition: TestResult.h:26
simulated2D::prior
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:88
gtsam
traits
Definition: chartTesting.h:28
gtsam::Values
Definition: Values.h:65
simulated2D::odo
Point2 odo(const Point2 &x1, const Point2 &x2)
odometry between two poses
Definition: simulated2D.h:99
A1
static const double A1[]
Definition: expn.h:6
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::Point3
Vector3 Point3
Definition: Point3.h:38
x2
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Pose3.h
3D Pose


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:10:25