testCal3_S2Stereo.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 Cal3_S2Stereo K(500, 500, 0.1, 640 / 2, 480 / 2, 1);
29 static Point2 p(1, -2);
30 static Point2 p_uv(1320.3, 1740);
31 static Point2 p_xy(2, 3);
32 
33 /* ************************************************************************* */
34 TEST(Cal3_S2Stereo, Constructor) {
35  Cal3_S2Stereo expected(554.256, 554.256, 0, 640 / 2, 480 / 2, 3);
36 
37  double fov = 60; // degrees
38  size_t w = 640, h = 480;
39  Cal3_S2Stereo actual(fov, w, h, 3);
40 
41  CHECK(assert_equal(expected, actual, 1e-3));
42 }
43 
44 /* ************************************************************************* */
45 TEST(Cal3_S2Stereo, Calibrate) {
46  Point2 intrinsic(2, 3);
47  Point2 expectedimage(1320.3, 1740);
48  Point2 imagecoordinates = K.uncalibrate(intrinsic);
49  CHECK(assert_equal(expectedimage, imagecoordinates));
50  CHECK(assert_equal(intrinsic, K.calibrate(imagecoordinates)));
51 }
52 
53 /* ************************************************************************* */
54 TEST(Cal3_S2Stereo, CalibrateHomogeneous) {
55  Vector3 intrinsic(2, 3, 1);
56  Vector3 image(1320.3, 1740, 1);
57  CHECK(assert_equal(intrinsic, K.calibrate(image)));
58 }
59 
60 /* ************************************************************************* */
62  return k.uncalibrate(pt);
63 }
64 
65 TEST(Cal3_S2Stereo, Duncalibrate) {
66  Matrix26 Dcal;
67  Matrix22 Dp;
68  K.uncalibrate(p, Dcal, Dp);
69 
71  CHECK(assert_equal(numerical1, Dcal, 1e-8));
73  CHECK(assert_equal(numerical2, Dp, 1e-9));
74 }
75 
77  return K.calibrate(pt);
78 }
79 /* ************************************************************************* */
80 TEST(Cal3_S2Stereo, Dcalibrate) {
81  Matrix26 Dcal;
82  Matrix22 Dp;
83  Point2 expected = K.calibrate(p_uv, Dcal, Dp);
85 
87  CHECK(assert_equal(numerical1, Dcal, 1e-8));
89  CHECK(assert_equal(numerical2, Dp, 1e-8));
90 }
91 
92 /* ************************************************************************* */
94  CHECK(assert_equal(K, K, 1e-9));
95 
96  Cal3_S2Stereo K1(500, 500, 0.1, 640 / 2, 480 / 2, 1);
97  CHECK(assert_equal(K, K1, 1e-9));
98 }
99 
100 /* ************************************************************************* */
101 TEST(Cal3_S2Stereo, Retract) {
102  Cal3_S2Stereo expected(500 + 1, 500 + 2, 0.1 + 3, 640 / 2 + 4, 480 / 2 + 5,
103  7);
105  EXPECT_LONGS_EQUAL(expected.dim(), 6);
106 
107  Vector6 d;
108  d << 1, 2, 3, 4, 5, 6;
109  Cal3_S2Stereo actual = K.retract(d);
110  CHECK(assert_equal(expected, actual, 1e-7));
111  CHECK(assert_equal(d, K.localCoordinates(actual), 1e-7));
112 }
113 
114 /* ************************************************************************* */
116  Cal3_S2Stereo cal(5, 5, 5, 5, 5, 2);
117  std::stringstream os;
118  os << "fx: " << cal.fx() << ", fy: " << cal.fy() << ", s: " << cal.skew()
119  << ", px: " << cal.px() << ", py: " << cal.py()
120  << ", b: " << cal.baseline();
121  EXPECT(assert_stdout_equal(os.str(), cal));
122 }
123 
124 /* ************************************************************************* */
125 int main() {
126  TestResult tr;
127  return TestRegistry::runAllTests(tr);
128 }
129 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.cal
cal
Definition: test_ProjectionFactorRollingShutter.py:27
fov
static double fov
Definition: testProjectionFactor.cpp:33
gtsam::Cal3_S2Stereo::calibrate
Point2 calibrate(const Point2 &p, OptionalJacobian< 2, 6 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const
Definition: Cal3_S2Stereo.cpp:55
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
p
static Point2 p(1, -2)
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
gtsam::Cal3_S2Stereo::Dim
static size_t Dim()
return DOF, dimensionality of tangent space
Definition: Cal3_S2Stereo.h:128
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
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
calibrate_
Point2 calibrate_(const Cal3_S2Stereo &K, const Point2 &pt)
Definition: testCal3_S2Stereo.cpp:76
h
const double h
Definition: testSimpleHelicopter.cpp:19
os
ofstream os("timeSchurFactors.csv")
TestableAssertions.h
Provides additional testing facilities for common data structures.
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
gtsam::Cal3_S2Stereo::uncalibrate
Point2 uncalibrate(const Point2 &p, OptionalJacobian< 2, 6 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const
Definition: Cal3_S2Stereo.cpp:46
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
Cal3_S2Stereo.h
The most common 5DOF 3D->2D calibration + Stereo baseline.
p_uv
static Point2 p_uv(1320.3, 1740)
K1
static Cal3_S2::shared_ptr K1(new Cal3_S2(fov, w, h))
main
int main()
Definition: testCal3_S2Stereo.cpp:125
TestResult
Definition: TestResult.h:26
gtsam
traits
Definition: chartTesting.h:28
gtsam::TEST
TEST(SmartFactorBase, Pinhole)
Definition: testSmartFactorBase.cpp:38
gtsam::Cal3_S2Stereo
The most common 5DOF 3D->2D calibration, stereo version.
Definition: Cal3_S2Stereo.h:30
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
uncalibrate_
Point2 uncalibrate_(const Cal3_S2Stereo &k, const Point2 &pt)
Definition: testCal3_S2Stereo.cpp:61
gtsam::Cal3_S2Stereo::localCoordinates
Vector6 localCoordinates(const Cal3_S2Stereo &T2) const
Unretraction for the calibration.
Definition: Cal3_S2Stereo.h:137
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_S2Stereo::retract
Cal3_S2Stereo retract(const Vector &d) const
Given 6-dim tangent vector, create new calibration.
Definition: Cal3_S2Stereo.h:131
p_xy
static Point2 p_xy(2, 3)
K
static Cal3_S2Stereo K(500, 500, 0.1, 640/2, 480/2, 1)


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