testCal3DS2.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>
21 #include <gtsam/geometry/Cal3DS2.h>
22 
23 using namespace gtsam;
24 
27 
28 static Cal3DS2 K(500, 100, 0.1, 320, 240, 1e-3, 2.0 * 1e-3, 3.0 * 1e-3,
29  4.0 * 1e-3);
30 static Point2 p(2, 3);
31 
32 /* ************************************************************************* */
33 TEST(Cal3DS2, Uncalibrate) {
34  Vector k = K.k();
35  double r = p.x() * p.x() + p.y() * p.y();
36  double g = 1 + k[0] * r + k[1] * r * r;
37  double tx = 2 * k[2] * p.x() * p.y() + k[3] * (r + 2 * p.x() * p.x());
38  double ty = k[2] * (r + 2 * p.y() * p.y()) + 2 * k[3] * p.x() * p.y();
39  Vector v_hat = (Vector(3) << g * p.x() + tx, g * p.y() + ty, 1.0).finished();
40  Vector v_i = K.K() * v_hat;
41  Point2 p_i(v_i(0) / v_i(2), v_i(1) / v_i(2));
42  Point2 q = K.uncalibrate(p);
43  CHECK(assert_equal(q, p_i));
44 }
45 
46 TEST(Cal3DS2, Calibrate) {
47  Point2 pn(0.5, 0.5);
48  Point2 pi = K.uncalibrate(pn);
49  Point2 pn_hat = K.calibrate(pi);
50  CHECK(traits<Point2>::Equals(pn, pn_hat, 1e-5));
51 }
52 
53 Point2 uncalibrate_(const Cal3DS2& k, const Point2& pt) {
54  return k.uncalibrate(pt);
55 }
56 
57 /* ************************************************************************* */
58 TEST(Cal3DS2, Duncalibrate1) {
59  Matrix computed;
60  K.uncalibrate(p, computed, {});
61  Matrix numerical = numericalDerivative21(uncalibrate_, K, p, 1e-7);
62  CHECK(assert_equal(numerical, computed, 1e-5));
63  Matrix separate = K.D2d_calibration(p);
64  CHECK(assert_equal(numerical, separate, 1e-5));
65 }
66 
67 /* ************************************************************************* */
68 TEST(Cal3DS2, Duncalibrate2) {
69  Matrix computed;
70  K.uncalibrate(p, {}, computed);
71  Matrix numerical = numericalDerivative22(uncalibrate_, K, p, 1e-7);
72  CHECK(assert_equal(numerical, computed, 1e-5));
73  Matrix separate = K.D2d_intrinsic(p);
74  CHECK(assert_equal(numerical, separate, 1e-5));
75 }
76 
77 Point2 calibrate_(const Cal3DS2& k, const Point2& pt) {
78  return k.calibrate(pt);
79 }
80 
81 /* ************************************************************************* */
82 TEST(Cal3DS2, Dcalibrate) {
83  Point2 pn(0.5, 0.5);
84  Point2 pi = K.uncalibrate(pn);
85  Matrix Dcal, Dp;
86  K.calibrate(pi, Dcal, Dp);
87  Matrix numerical1 = numericalDerivative21(calibrate_, K, pi, 1e-7);
88  CHECK(assert_equal(numerical1, Dcal, 1e-5));
89  Matrix numerical2 = numericalDerivative22(calibrate_, K, pi, 1e-7);
90  CHECK(assert_equal(numerical2, Dp, 1e-5));
91 }
92 
93 /* ************************************************************************* */
94 TEST(Cal3DS2, Equal) { CHECK(assert_equal(K, K, 1e-5)); }
95 
96 /* ************************************************************************* */
97 TEST(Cal3DS2, Retract) {
98  Cal3DS2 expected(500 + 1, 100 + 2, 0.1 + 3, 320 + 4, 240 + 5, 1e-3 + 6,
99  2.0 * 1e-3 + 7, 3.0 * 1e-3 + 8, 4.0 * 1e-3 + 9);
100 
102  EXPECT_LONGS_EQUAL(expected.dim(), 9);
103 
104  Vector9 d;
105  d << 1, 2, 3, 4, 5, 6, 7, 8, 9;
106  Cal3DS2 actual = K.retract(d);
107  CHECK(assert_equal(expected, actual, 1e-7));
108  CHECK(assert_equal(d, K.localCoordinates(actual), 1e-7));
109 }
110 
111 /* ************************************************************************* */
113  Cal3DS2 cal(1, 2, 3, 4, 5, 6, 7, 8, 9);
114  std::stringstream os;
115  os << "fx: " << cal.fx() << ", fy: " << cal.fy() << ", s: " << cal.skew()
116  << ", px: " << cal.px() << ", py: " << cal.py() << ", k1: " << cal.k1()
117  << ", k2: " << cal.k2() << ", p1: " << cal.p1() << ", p2: " << cal.p2();
118 
119  EXPECT(assert_stdout_equal(os.str(), cal));
120 }
121 
122 /* ************************************************************************* */
123 int main() {
124  TestResult tr;
125  return TestRegistry::runAllTests(tr);
126 }
127 /* ************************************************************************* */
gtsam::Cal3::fy
double fy() const
focal length y
Definition: Cal3.h:142
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
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.
gtsam::Cal3DS2::localCoordinates
Vector localCoordinates(const Cal3DS2 &T2) const
Given a different calibration, calculate update to obtain it.
Definition: Cal3DS2.cpp:48
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Cal3DS2
Calibration of a camera with radial distortion that also supports Lie-group behaviors for optimizatio...
Definition: Cal3DS2.h:35
TestHarness.h
gtsam::Cal3::py
double py() const
image center in y
Definition: Cal3.h:154
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
calibrate_
Point2 calibrate_(const Cal3DS2 &k, const Point2 &pt)
Definition: testCal3DS2.cpp:77
os
ofstream os("timeSchurFactors.csv")
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::Cal3DS2_Base::D2d_intrinsic
Matrix2 D2d_intrinsic(const Point2 &p) const
Derivative of uncalibrate wrpt intrinsic coordinates.
Definition: Cal3DS2_Base.cpp:169
uncalibrate_
Point2 uncalibrate_(const Cal3DS2 &k, const Point2 &pt)
Definition: testCal3DS2.cpp:53
fixture::cal
const Cal3_S2 cal(focalLength, focalLength, 0.0, principalPoint.x(), principalPoint.y())
TestableAssertions.h
Provides additional testing facilities for common data structures.
gtsam::Cal3DS2::Dim
static size_t Dim()
Return dimensions of calibration manifold object.
Definition: Cal3DS2.h:90
gtsam::Cal3DS2_Base::k
Vector4 k() const
return distortion parameter vector
Definition: Cal3DS2_Base.h:113
p
static Point2 p(2, 3)
gtsam::Cal3DS2::retract
Cal3DS2 retract(const Vector &d) const
Given delta vector, update calibration.
Definition: Cal3DS2.cpp:43
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
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::Cal3::K
virtual Matrix3 K() const
return calibration matrix K
Definition: Cal3.h:167
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
TestResult
Definition: TestResult.h:26
gtsam::Cal3::fx
double fx() const
focal length x
Definition: Cal3.h:139
gtsam
traits
Definition: SFMdata.h:40
gtsam::TEST
TEST(SmartFactorBase, Pinhole)
Definition: testSmartFactorBase.cpp:38
gtsam::traits
Definition: Group.h:36
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
Cal3DS2.h
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
gtsam::Cal3DS2_Base::calibrate
Point2 calibrate(const Point2 &p, OptionalJacobian< 2, 9 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const
Convert (distorted) image coordinates uv to intrinsic coordinates xy.
Definition: Cal3DS2_Base.cpp:133
gtsam::Cal3::skew
double skew() const
skew
Definition: Cal3.h:148
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::Cal3::px
double px() const
image center in x
Definition: Cal3.h:151
main
int main()
Definition: testCal3DS2.cpp:123
gtsam::Cal3DS2_Base::uncalibrate
Point2 uncalibrate(const Point2 &p, OptionalJacobian< 2, 9 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const
Definition: Cal3DS2_Base.cpp:94
gtsam::Cal3DS2_Base::D2d_calibration
Matrix29 D2d_calibration(const Point2 &p) const
Derivative of uncalibrate wrpt the calibration parameters.
Definition: Cal3DS2_Base.cpp:180
K
static Cal3DS2 K(500, 100, 0.1, 320, 240, 1e-3, 2.0 *1e-3, 3.0 *1e-3, 4.0 *1e-3)


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:07:19