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 
24 using namespace std;
25 using namespace gtsam;
26 
27 /* ************************************************************************* */
29 TEST(PinholeSet, Stereo) {
30  typedef Point2Vector ZZ;
33  set.push_back(camera);
34  set.push_back(camera);
35  // set.print("set: ");
36  Point3 p(0, 0, 1);
38 
39  // Check measurements
40  Point2 expected(0, 0);
41  ZZ z = set.project2(p);
44 
45  // Calculate expected derivatives using Pinhole
46  Matrix43 actualE;
47  Matrix F1;
48  {
49  Matrix23 E1;
50  camera.project2(p, F1, E1);
51  actualE << E1, E1;
52  }
53 
54  // Check computed derivatives
56  Matrix E;
57  set.project2(p, Fs, E);
58  LONGS_EQUAL(2, Fs.size());
59  EXPECT(assert_equal(F1, Fs[0]));
60  EXPECT(assert_equal(F1, Fs[1]));
61  EXPECT(assert_equal(actualE, E));
62 
63  // Instantiate triangulateSafe
64  // TODO triangulation does not work yet for CalibratedCamera
65  // PinholeSet<CalibratedCamera>::Result actual = set.triangulateSafe(z);
66 }
67 
68 /* ************************************************************************* */
69 // Cal3Bundler test
72 TEST(PinholeSet, Pinhole) {
74  typedef Point2Vector ZZ;
76  Camera camera;
77  set.push_back(camera);
78  set.push_back(camera);
79  Point3 p(0, 0, 1);
81  PinholeSet<Camera> set2 = set;
82  set2.push_back(camera);
83  EXPECT(!set.equals(set2));
84 
85  // Check measurements
86  Point2 expected(0,0);
87  ZZ z = set.project2(p);
90 
91  // Calculate expected derivatives using Pinhole
92  Matrix actualE;
93  Matrix F1;
94  {
95  Matrix23 E1;
96  camera.project2(p, F1, E1);
97  actualE.resize(4, 3);
98  actualE << E1, E1;
99  }
100 
101  // Check computed derivatives
102  {
104  Matrix E;
105  set.project2(p, Fs, E);
106  EXPECT(assert_equal(actualE, E));
107  LONGS_EQUAL(2, Fs.size());
108  EXPECT(assert_equal(F1, Fs[0]));
109  EXPECT(assert_equal(F1, Fs[1]));
110  }
111 
112  // Check errors
113  ZZ measured;
114  measured.push_back(Point2(1, 2));
115  measured.push_back(Point2(3, 4));
116  Vector4 expectedV;
117 
118  // reprojectionError
119  expectedV << -1, -2, -3, -4;
120  Vector actualV = set.reprojectionError(p, measured);
121  EXPECT(assert_equal(expectedV, actualV));
122 
123  // reprojectionErrorAtInfinity
124  Unit3 pointAtInfinity(0, 0, 1000);
125  {
126  Matrix22 E1;
128  actualE.resize(4, 2);
129  actualE << E1, E1;
130  }
131  EXPECT(
133  camera.backprojectPointAtInfinity(Point2(0,0))));
134  {
136  Matrix E;
137  actualV = set.reprojectionError(pointAtInfinity, measured, Fs, E);
138  EXPECT(assert_equal(actualE, E));
139  LONGS_EQUAL(2, Fs.size());
140  EXPECT(assert_equal(F1, Fs[0]));
141  EXPECT(assert_equal(F1, Fs[1]));
142  }
143  EXPECT(assert_equal(expectedV, actualV));
144 
145  // Instantiate triangulateSafe
147  TriangulationResult actual = set.triangulateSafe(z, params);
148  CHECK(actual.degenerate());
149 }
150 
151 /* ************************************************************************* */
152 int main() {
153  TestResult tr;
154  return TestRegistry::runAllTests(tr);
155 }
156 /* ************************************************************************* */
157 
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
PinholeSet.h
A CameraSet of either CalibratedCamera, PinholePose, or PinholeCamera.
main
int main()
Definition: testPinholeSet.cpp:152
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
Camera
Definition: camera.h:36
measured
Point2 measured(-17, 30)
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
CalibratedCamera.h
Calibrated camera for which only pose is unknown.
gtsam::TriangulationParameters
Definition: triangulation.h:558
numericalDerivative.h
Some functions to compute numerical derivatives.
gtsam::PinholeCamera< Cal3Bundler >
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
PinholeCamera.h
Base class for all pinhole cameras.
pybind_wrapper_test_script.z
z
Definition: pybind_wrapper_test_script.py:61
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::CalibratedCamera
Definition: CalibratedCamera.h:251
F1
const Matrix26 F1
Definition: testRegularImplicitSchurFactor.cpp:37
TEST
TEST(PinholeSet, Stereo)
Definition: testPinholeSet.cpp:29
TestResult
Definition: TestResult.h:26
gtsam::TriangulationResult::degenerate
bool degenerate() const
Definition: triangulation.h:667
set
void set(Container &c, Position position, const Value &value)
Definition: stdlist_overload.cpp:37
E
DiscreteKey E(5, 2)
gtsam
traits
Definition: SFMdata.h:40
gtsam::traits
Definition: Group.h:36
CHECK
#define CHECK(condition)
Definition: Test.h:108
std
Definition: BFloat16.h:88
gtsam::PinholeBase::project2
Point2 project2(const Point3 &point, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}) const
Definition: CalibratedCamera.cpp:116
p
float * p
Definition: Tutorial_Map_using.cpp:9
Camera
PinholePose< Cal3_S2 > Camera
Definition: SFMExample_SmartFactor.cpp:38
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::Point2Vector
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
Definition: Point2.h:49
gtsam::TriangulationResult
Definition: triangulation.h:638
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
camera
static const CalibratedCamera camera(kDefaultPose)
pointAtInfinity
Unit3 pointAtInfinity(0, 0, -1000)
Cal3Bundler.h
Calibration used by Bundler.
LONGS_EQUAL
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:134
gtsam::PinholeSet
Definition: PinholeSet.h:29
Pose3.h
3D Pose
E1
E1
Definition: test_numpy_dtypes.cpp:102


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:06