testPinholeSet.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 
20 #include <gtsam/geometry/Pose3.h>
23 #include <boost/bind.hpp>
24 
25 using namespace std;
26 using namespace gtsam;
27 
28 /* ************************************************************************* */
30 TEST(PinholeSet, Stereo) {
31  typedef Point2Vector ZZ;
34  set.push_back(camera);
35  set.push_back(camera);
36  // set.print("set: ");
37  Point3 p(0, 0, 1);
39 
40  // Check measurements
41  Point2 expected(0, 0);
42  ZZ z = set.project2(p);
43  EXPECT(assert_equal(expected, z[0]));
44  EXPECT(assert_equal(expected, z[1]));
45 
46  // Calculate expected derivatives using Pinhole
47  Matrix43 actualE;
48  Matrix F1;
49  {
50  Matrix23 E1;
51  camera.project2(p, F1, E1);
52  actualE << E1, E1;
53  }
54 
55  // Check computed derivatives
57  Matrix E;
58  set.project2(p, Fs, E);
59  LONGS_EQUAL(2, Fs.size());
60  EXPECT(assert_equal(F1, Fs[0]));
61  EXPECT(assert_equal(F1, Fs[1]));
62  EXPECT(assert_equal(actualE, E));
63 
64  // Instantiate triangulateSafe
65  // TODO triangulation does not work yet for CalibratedCamera
66  // PinholeSet<CalibratedCamera>::Result actual = set.triangulateSafe(z);
67 }
68 
69 /* ************************************************************************* */
70 // Cal3Bundler test
73 TEST(PinholeSet, Pinhole) {
75  typedef Point2Vector ZZ;
77  Camera camera;
78  set.push_back(camera);
79  set.push_back(camera);
80  Point3 p(0, 0, 1);
81  EXPECT(assert_equal(set, set));
82  PinholeSet<Camera> set2 = set;
83  set2.push_back(camera);
84  EXPECT(!set.equals(set2));
85 
86  // Check measurements
87  Point2 expected(0,0);
88  ZZ z = set.project2(p);
89  EXPECT(assert_equal(expected, z[0]));
90  EXPECT(assert_equal(expected, z[1]));
91 
92  // Calculate expected derivatives using Pinhole
93  Matrix actualE;
94  Matrix F1;
95  {
96  Matrix23 E1;
97  camera.project2(p, F1, E1);
98  actualE.resize(4, 3);
99  actualE << E1, E1;
100  }
101 
102  // Check computed derivatives
103  {
105  Matrix E;
106  set.project2(p, Fs, E);
107  EXPECT(assert_equal(actualE, E));
108  LONGS_EQUAL(2, Fs.size());
109  EXPECT(assert_equal(F1, Fs[0]));
110  EXPECT(assert_equal(F1, Fs[1]));
111  }
112 
113  // Check errors
114  ZZ measured;
115  measured.push_back(Point2(1, 2));
116  measured.push_back(Point2(3, 4));
117  Vector4 expectedV;
118 
119  // reprojectionError
120  expectedV << -1, -2, -3, -4;
121  Vector actualV = set.reprojectionError(p, measured);
122  EXPECT(assert_equal(expectedV, actualV));
123 
124  // reprojectionErrorAtInfinity
125  Unit3 pointAtInfinity(0, 0, 1000);
126  {
127  Matrix22 E1;
128  camera.project2(pointAtInfinity, F1, E1);
129  actualE.resize(4, 2);
130  actualE << E1, E1;
131  }
132  EXPECT(
133  assert_equal(pointAtInfinity,
134  camera.backprojectPointAtInfinity(Point2(0,0))));
135  {
137  Matrix E;
138  actualV = set.reprojectionError(pointAtInfinity, measured, Fs, E);
139  EXPECT(assert_equal(actualE, E));
140  LONGS_EQUAL(2, Fs.size());
141  EXPECT(assert_equal(F1, Fs[0]));
142  EXPECT(assert_equal(F1, Fs[1]));
143  }
144  EXPECT(assert_equal(expectedV, actualV));
145 
146  // Instantiate triangulateSafe
148  TriangulationResult actual = set.triangulateSafe(z, params);
149  CHECK(actual.degenerate());
150 }
151 
152 /* ************************************************************************* */
153 int main() {
154  TestResult tr;
155  return TestRegistry::runAllTests(tr);
156 }
157 /* ************************************************************************* */
158 
#define CHECK(condition)
Definition: Test.h:109
Key E(std::uint64_t j)
static int runAllTests(TestResult &result)
Matrix expected
Definition: testMatrix.cpp:974
Point2 project2(const Point3 &point, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
Vector2 Point2
Definition: Point2.h:27
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Definition: Half.h:150
Some functions to compute numerical derivatives.
const Matrix26 F1
Unit3 pointAtInfinity(0, 0,-1000)
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Base class for all pinhole cameras.
Eigen::VectorXd Vector
Definition: Vector.h:38
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
Definition: Point2.h:42
#define EXPECT(condition)
Definition: Test.h:151
A CameraSet of either CalibratedCamera, PinholePose, or PinholeCamera.
static SmartStereoProjectionParams params
Calibrated camera for which only pose is unknown.
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:135
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
float * p
TEST(PinholeSet, Stereo)
int main()
PinholePose< Cal3_S2 > Camera
Vector3 Point3
Definition: Point3.h:35
Point3 measured
static const CalibratedCamera camera(kDefaultPose)
3D Pose
Calibration used by Bundler.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:48:34