testCal3Bundler.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 using namespace gtsam;
24 
27 
28 static Cal3Bundler K(500, 1e-3, 1e-3, 1000, 2000);
29 static Point2 p(2, 3);
30 
31 /* ************************************************************************* */
32 TEST(Cal3Bundler, vector) {
33  Cal3Bundler K;
34  Vector expected(3);
35  expected << 1, 0, 0;
36  CHECK(assert_equal(expected, K.vector()));
37 }
38 
39 /* ************************************************************************* */
41  Vector v = K.vector();
42  double r = p.x() * p.x() + p.y() * p.y();
43  double g = v[0] * (1 + v[1] * r + v[2] * r * r);
44  Point2 expected(1000 + g * p.x(), 2000 + g * p.y());
45  Point2 actual = K.uncalibrate(p);
46  CHECK(assert_equal(expected, actual));
47 }
48 
49 TEST(Cal3Bundler, calibrate) {
50  Point2 pn(0.5, 0.5);
51  Point2 pi = K.uncalibrate(pn);
52  Point2 pn_hat = K.calibrate(pi);
53  CHECK(traits<Point2>::Equals(pn, pn_hat, 1e-5));
54 }
55 
56 /* ************************************************************************* */
58  return k.uncalibrate(pt);
59 }
60 
61 Point2 calibrate_(const Cal3Bundler& k, const Point2& pt) {
62  return k.calibrate(pt);
63 }
64 
65 /* ************************************************************************* */
66 TEST(Cal3Bundler, Duncalibrate) {
67  Matrix Dcal, Dp;
68  Point2 actual = K.uncalibrate(p, Dcal, Dp);
69  Point2 expected(2182, 3773);
70  CHECK(assert_equal(expected, actual, 1e-7));
73  CHECK(assert_equal(numerical1, Dcal, 1e-7));
74  CHECK(assert_equal(numerical2, Dp, 1e-7));
75 }
76 
77 /* ************************************************************************* */
78 TEST(Cal3Bundler, Dcalibrate) {
79  Matrix Dcal, Dp;
80  Point2 pn(0.5, 0.5);
81  Point2 pi = K.uncalibrate(pn);
82  Point2 actual = K.calibrate(pi, Dcal, Dp);
83  CHECK(assert_equal(pn, actual, 1e-7));
84  Matrix numerical1 = numericalDerivative21(calibrate_, K, pi);
85  Matrix numerical2 = numericalDerivative22(calibrate_, K, pi);
86  CHECK(assert_equal(numerical1, Dcal, 1e-5));
87  CHECK(assert_equal(numerical2, Dp, 1e-5));
88 }
89 
90 /* ************************************************************************* */
92 
93 /* ************************************************************************* */
94 TEST(Cal3Bundler, retract) {
95  Cal3Bundler expected(510, 2e-3, 2e-3, 1000, 2000);
96  EXPECT_LONGS_EQUAL(3, expected.dim());
97 
99  EXPECT_LONGS_EQUAL(expected.dim(), 3);
100 
101  Vector3 d;
102  d << 10, 1e-3, 1e-3;
103  Cal3Bundler actual = K.retract(d);
104  CHECK(assert_equal(expected, actual, 1e-7));
105  CHECK(assert_equal(d, K.localCoordinates(actual), 1e-7));
106 }
107 
108 /* ************************************************************************* */
110  Cal3Bundler cal(1, 2, 3, 4, 5);
111  std::stringstream os;
112  os << "f: " << cal.fx() << ", k1: " << cal.k1() << ", k2: " << cal.k2()
113  << ", px: " << cal.px() << ", py: " << cal.py();
114 
115  EXPECT(assert_stdout_equal(os.str(), cal));
116 }
117 
118 /* ************************************************************************* */
119 int main() {
120  TestResult tr;
121  return TestRegistry::runAllTests(tr);
122 }
123 /* ************************************************************************* */
bool assert_stdout_equal(const std::string &expected, const V &actual)
Provides additional testing facilities for common data structures.
#define CHECK(condition)
Definition: Test.h:109
Vector3 vector() const
Definition: Cal3Bundler.cpp:42
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
double k1() const
distorsion parameter k1
Definition: Cal3Bundler.h:84
Matrix expected
Definition: testMatrix.cpp:974
int main()
Vector2 Point2
Definition: Point2.h:27
ArrayXcf v
Definition: Cwise_arg.cpp:1
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
double k2() const
distorsion parameter k2
Definition: Cal3Bundler.h:87
Some functions to compute numerical derivatives.
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const boost::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
static const Point3 pt(1.0, 2.0, 3.0)
void g(const string &key, int i)
Definition: testBTree.cpp:43
Cal3Bundler retract(const Vector &d) const
Update calibration with tangent space delta.
Definition: Cal3Bundler.h:150
Point2 calibrate(const Point2 &pi, OptionalJacobian< 2, 3 > Dcal=boost::none, OptionalJacobian< 2, 2 > Dp=boost::none) const
Definition: Cal3Bundler.cpp:95
Eigen::VectorXd Vector
Definition: Vector.h:38
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
static Cal3Bundler K(500, 1e-3, 1e-3, 1000, 2000)
#define EXPECT(condition)
Definition: Test.h:151
Array< double, 1, 3 > e(1./3., 0.5, 2.)
double px() const
image center in x
Definition: Cal3Bundler.h:90
Point2 uncalibrate_(const Cal3Bundler &k, const Point2 &pt)
size_t dim() const override
return DOF, dimensionality of tangent space
Definition: Cal3Bundler.h:144
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
#define GTSAM_CONCEPT_MANIFOLD_INST(T)
Definition: Manifold.h:180
static Point2 p(2, 3)
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
ofstream os("timeSchurFactors.csv")
Vector3 localCoordinates(const Cal3Bundler &T2) const
Calculate local coordinates to another calibration.
Definition: Cal3Bundler.h:155
Point2_ uncalibrate(const Expression< CALIBRATION > &K, const Point2_ &xy_hat)
TEST(LPInitSolver, InfiniteLoopSingleVar)
double fx() const
focal length x
Definition: Cal3.h:139
static size_t Dim()
return DOF, dimensionality of tangent space
Definition: Cal3Bundler.h:147
double py() const
image center in y
Definition: Cal3Bundler.h:93
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:59
Calibration used by Bundler.
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:174
Point2 uncalibrate(const Point2 &p, OptionalJacobian< 2, 3 > Dcal=boost::none, OptionalJacobian< 2, 2 > Dp=boost::none) const
: convert intrinsic coordinates xy to image coordinates uv Version of uncalibrate with derivatives ...
Definition: Cal3Bundler.cpp:66
Point2 calibrate_(const Cal3Bundler &k, const Point2 &pt)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:21