testCal3Unified.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 <gtsam/base/Testable.h>
22 
23 #include <gtsam/inference/Key.h>
24 #include <gtsam/nonlinear/Values.h>
25 
26 using namespace gtsam;
27 
30 
31 /*
32 ground truth from matlab, code :
33 X = [0.5 0.7 1]';
34 V = [0.1, 1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3, 0, 0, 100, 105, 320, 240];
35 [P, J] = spaceToImgPlane(X, V);
36 matlab toolbox available at http://homepages.laas.fr/~cmei/index.php/Toolbox
37 */
38 
39 static Cal3Unified K(100, 105, 0.0, 320, 240, 1e-3, 2.0 * 1e-3, 3.0 * 1e-3,
40  4.0 * 1e-3, 0.1);
41 static Point2 p(0.5, 0.7);
42 
43 /* ************************************************************************* */
44 TEST(Cal3Unified, Uncalibrate) {
45  Point2 p_i(364.7791831734982, 305.6677211952602);
46  Point2 q = K.uncalibrate(p);
47  CHECK(assert_equal(q, p_i));
48 }
49 
50 /* ************************************************************************* */
51 TEST(Cal3Unified, SpaceNplane) {
53  CHECK(assert_equal(Point2(0.441731600049497, 0.618424240069295), q));
55 }
56 
57 /* ************************************************************************* */
58 TEST(Cal3Unified, Calibrate) {
59  Point2 pi = K.uncalibrate(p);
60  Point2 pn_hat = K.calibrate(pi);
61  CHECK(traits<Point2>::Equals(p, pn_hat, 1e-8));
62 }
63 
65  return k.uncalibrate(pt);
66 }
67 
68 /* ************************************************************************* */
69 TEST(Cal3Unified, Duncalibrate1) {
70  Matrix computed;
71  K.uncalibrate(p, computed, {});
72  Matrix numerical = numericalDerivative21(uncalibrate_, K, p, 1e-7);
73  CHECK(assert_equal(numerical, computed, 1e-6));
74 }
75 
76 /* ************************************************************************* */
77 TEST(Cal3Unified, Duncalibrate2) {
78  Matrix computed;
79  K.uncalibrate(p, {}, computed);
80  Matrix numerical = numericalDerivative22(uncalibrate_, K, p, 1e-7);
81  CHECK(assert_equal(numerical, computed, 1e-6));
82 }
83 
84 Point2 calibrate_(const Cal3Unified& k, const Point2& pt) {
85  return k.calibrate(pt);
86 }
87 
88 /* ************************************************************************* */
89 TEST(Cal3Unified, Dcalibrate) {
90  Point2 pi = K.uncalibrate(p);
91  Matrix Dcal, Dp;
92  K.calibrate(pi, Dcal, Dp);
93  Matrix numerical1 = numericalDerivative21(calibrate_, K, pi);
94  CHECK(assert_equal(numerical1, Dcal, 1e-5));
95  Matrix numerical2 = numericalDerivative22(calibrate_, K, pi);
96  CHECK(assert_equal(numerical2, Dp, 1e-5));
97 }
98 
99 /* ************************************************************************* */
100 TEST(Cal3Unified, Equal) { CHECK(assert_equal(K, K, 1e-9)); }
101 
102 /* ************************************************************************* */
103 TEST(Cal3Unified, Retract) {
104  Cal3Unified expected(100 + 2, 105 + 3, 0.0 + 4, 320 + 5, 240 + 6, 1e-3 + 7,
105  2.0 * 1e-3 + 8, 3.0 * 1e-3 + 9, 4.0 * 1e-3 + 10,
106  0.1 + 1);
107 
109  EXPECT_LONGS_EQUAL(expected.dim(), 10);
110 
111  Vector10 d;
112  d << 2, 3, 4, 5, 6, 7, 8, 9, 10, 1;
113  Cal3Unified actual = K.retract(d);
114  CHECK(assert_equal(expected, actual, 1e-9));
115  CHECK(assert_equal(d, K.localCoordinates(actual), 1e-9));
116 }
117 
118 /* ************************************************************************* */
119 TEST(Cal3Unified, DerivedValue) {
120  Values values;
121  Cal3Unified cal(1, 2, 3, 4, 5, 6, 7, 8, 9, 10);
122  Key key = 1;
123  values.insert(key, cal);
124 
125  Cal3Unified calafter = values.at<Cal3Unified>(key);
126 
127  CHECK(assert_equal(cal, calafter, 1e-9));
128 }
129 
130 /* ************************************************************************* */
132  Cal3Unified cal(0, 1, 2, 3, 4, 5, 6, 7, 8, 9);
133  std::stringstream os;
134  os << "fx: " << cal.fx() << ", fy: " << cal.fy() << ", s: " << cal.skew()
135  << ", px: " << cal.px() << ", py: " << cal.py() << ", k1: " << cal.k1()
136  << ", k2: " << cal.k2() << ", p1: " << cal.p1() << ", p2: " << cal.p2()
137  << ", xi: " << cal.xi();
138 
139  EXPECT(assert_stdout_equal(os.str(), cal));
140 }
141 
142 /* ************************************************************************* */
143 int main() {
144  TestResult tr;
145  return TestRegistry::runAllTests(tr);
146 }
147 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.cal
cal
Definition: test_ProjectionFactorRollingShutter.py:27
gtsam::Cal3Unified::uncalibrate
Point2 uncalibrate(const Point2 &p, OptionalJacobian< 2, 10 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const
Definition: Cal3Unified.cpp:56
main
int main()
Definition: testCal3Unified.cpp:143
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
GTSAM_CONCEPT_TESTABLE_INST
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:176
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
Testable.h
Concept check for values that can be used in unit tests.
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
uncalibrate_
Point2 uncalibrate_(const Cal3Unified &k, const Point2 &pt)
Definition: testCal3Unified.cpp:64
gtsam::numericalDerivative22
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:195
pt
static const Point3 pt(1.0, 2.0, 3.0)
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
K
static Cal3Unified K(100, 105, 0.0, 320, 240, 1e-3, 2.0 *1e-3, 3.0 *1e-3, 4.0 *1e-3, 0.1)
os
ofstream os("timeSchurFactors.csv")
TestableAssertions.h
Provides additional testing facilities for common data structures.
Key.h
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
numericalDerivative.h
Some functions to compute numerical derivatives.
gtsam::assert_stdout_equal
bool assert_stdout_equal(const std::string &expected, const V &actual)
Definition: TestableAssertions.h:330
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1984
gtsam::Cal3Unified::nPlaneToSpace
Point2 nPlaneToSpace(const Point2 &p) const
Convert a normalized unit plane point to 3D space.
Definition: Cal3Unified.cpp:116
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::Cal3Unified::calibrate
Point2 calibrate(const Point2 &p, OptionalJacobian< 2, 10 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const
Conver a pixel coordinate to ideal coordinate.
Definition: Cal3Unified.cpp:103
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::Cal3Unified::spaceToNPlane
Point2 spaceToNPlane(const Point2 &p) const
Convert a 3D point to normalized unit plane.
Definition: Cal3Unified.cpp:125
Cal3Unified.h
Unified Calibration Model, see Mei07icra for details.
TestResult
Definition: TestResult.h:26
key
const gtsam::Symbol key('X', 0)
gtsam
traits
Definition: chartTesting.h:28
gtsam::TEST
TEST(SmartFactorBase, Pinhole)
Definition: testSmartFactorBase.cpp:38
gtsam::traits
Definition: Group.h:36
p
static Point2 p(0.5, 0.7)
leaf::values
leaf::MyValues values
gtsam::Values
Definition: Values.h:65
CHECK
#define CHECK(condition)
Definition: Test.h:108
gtsam::numericalDerivative21
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:166
gtsam::Cal3Unified::localCoordinates
Vector localCoordinates(const Cal3Unified &T2) const
Given a different calibration, calculate update to obtain it.
Definition: Cal3Unified.cpp:138
gtsam::Cal3Unified
Calibration of a omni-directional camera with mirror + lens radial distortion.
Definition: Cal3Unified.h:45
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
gtsam::Print
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:65
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
GTSAM_CONCEPT_MANIFOLD_INST
#define GTSAM_CONCEPT_MANIFOLD_INST(T)
‍**
Definition: Manifold.h:177
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
calibrate_
Point2 calibrate_(const Cal3Unified &k, const Point2 &pt)
Definition: testCal3Unified.cpp:84
gtsam::Cal3Unified::Dim
static size_t Dim()
Return dimensions of calibration manifold object.
Definition: Cal3Unified.h:136
Values.h
A non-templated config holding any types of Manifold-group elements.
gtsam::Cal3Unified::retract
Cal3Unified retract(const Vector &d) const
Given delta vector, update calibration.
Definition: Cal3Unified.cpp:133


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