test_SfmData.py
Go to the documentation of this file.
1 """
2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
4 All Rights Reserved
5 
6 See LICENSE for the license information
7 
8 Unit tests for testing dataset access.
9 Author: Frank Dellaert (Python: Sushmita Warrier)
10 """
11 # pylint: disable=invalid-name, no-name-in-module, no-member
12 
13 from __future__ import print_function
14 
15 import unittest
16 
17 import gtsam
18 import numpy as np
19 from gtsam import Point2, Point3, SfmData, SfmTrack
20 from gtsam.utils.test_case import GtsamTestCase
21 
22 
24  """Tests for SfmData and SfmTrack modules."""
25 
26  def setUp(self):
27  """Initialize SfmData and SfmTrack"""
28  self.data = SfmData()
29  # initialize SfmTrack with 3D point
30  self.tracks = SfmTrack()
31 
32  def test_tracks(self):
33  """Test functions in SfmTrack"""
34  # measurement is of format (camera_idx, imgPoint)
35  # create arbitrary camera indices for two cameras
36  i1, i2 = 4, 5
37 
38  # create arbitrary image measurements for cameras i1 and i2
39  uv_i1 = Point2(12.6, 82)
40 
41  # translating point uv_i1 along X-axis
42  uv_i2 = Point2(24.88, 82)
43 
44  # add measurements to the track
45  self.tracks.addMeasurement(i1, uv_i1)
46  self.tracks.addMeasurement(i2, uv_i2)
47 
48  # Number of measurements in the track is 2
49  self.assertEqual(self.tracks.numberMeasurements(), 2)
50 
51  # camera_idx in the first measurement of the track corresponds to i1
52  cam_idx, img_measurement = self.tracks.measurement(0)
53  self.assertEqual(cam_idx, i1)
54  np.testing.assert_array_almost_equal(
55  Point3(0., 0., 0.),
56  self.tracks.point3()
57  )
58 
59  def test_data(self):
60  """Test functions in SfmData"""
61  # Create new track with 3 measurements
62  i1, i2, i3 = 3, 5, 6
63  uv_i1 = Point2(21.23, 45.64)
64 
65  # translating along X-axis
66  uv_i2 = Point2(45.7, 45.64)
67  uv_i3 = Point2(68.35, 45.64)
68 
69  # add measurements and arbitrary point to the track
70  measurements = [(i1, uv_i1), (i2, uv_i2), (i3, uv_i3)]
71  pt = Point3(1.0, 6.0, 2.0)
72  track2 = SfmTrack(pt)
73  track2.addMeasurement(i1, uv_i1)
74  track2.addMeasurement(i2, uv_i2)
75  track2.addMeasurement(i3, uv_i3)
76  self.data.addTrack(self.tracks)
77  self.data.addTrack(track2)
78 
79  # Number of tracks in SfmData is 2
80  self.assertEqual(self.data.numberTracks(), 2)
81 
82  # camera idx of first measurement of second track corresponds to i1
83  cam_idx, img_measurement = self.data.track(1).measurement(0)
84  self.assertEqual(cam_idx, i1)
85 
86  def test_Balbianello(self):
87  """ Check that we can successfully read a bundler file and create a
88  factor graph from it
89  """
90  # The structure where we will save the SfM data
91  filename = gtsam.findExampleDataFile("Balbianello.out")
92  sfm_data = SfmData.FromBundlerFile(filename)
93 
94  # Check number of things
95  self.assertEqual(5, sfm_data.numberCameras())
96  self.assertEqual(544, sfm_data.numberTracks())
97  track0 = sfm_data.track(0)
98  self.assertEqual(3, track0.numberMeasurements())
99 
100  # Check projection of a given point
101  self.assertEqual(0, track0.measurement(0)[0])
102  camera0 = sfm_data.camera(0)
103  expected = camera0.project(track0.point3())
104  actual = track0.measurement(0)[1]
105  self.gtsamAssertEquals(expected, actual, 1)
106 
107  # We share *one* noiseModel between all projection factors
109  2, 1.0) # one pixel in u and v
110 
111  # Convert to NonlinearFactorGraph
112  graph = sfm_data.sfmFactorGraph(model)
113  self.assertEqual(1419, graph.size()) # regression
114 
115  # Get initial estimate
116  values = gtsam.initialCamerasAndPointsEstimate(sfm_data)
117  self.assertEqual(549, values.size()) # regression
118 
119 
120 if __name__ == '__main__':
121  unittest.main()
test_SfmData.TestSfmData.test_tracks
def test_tracks(self)
Definition: test_SfmData.py:32
gtsam::initialCamerasAndPointsEstimate
Values initialCamerasAndPointsEstimate(const SfmData &db)
This function creates initial values for cameras and points from db.
Definition: SfmData.cpp:430
test_SfmData.TestSfmData.data
data
Definition: test_SfmData.py:28
test_SfmData.TestSfmData.setUp
def setUp(self)
Definition: test_SfmData.py:26
point3
static const Point3 point3(0.08, 0.08, 0.0)
gtsam::utils.test_case.GtsamTestCase.gtsamAssertEquals
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Definition: test_case.py:19
test_SfmData.TestSfmData
Definition: test_SfmData.py:23
test_SfmData.TestSfmData.test_data
def test_data(self)
Definition: test_SfmData.py:59
gtsam::SfmData
SfmData stores a bunch of SfmTracks.
Definition: SfmData.h:39
gtsam::SfmTrack
Definition: SfmTrack.h:125
addMeasurement
void addMeasurement(HybridBayesNet &hbn, Key z_key, Key x_key, double sigma)
Definition: testHybridMotionModel.cpp:49
gtsam::utils.test_case
Definition: test_case.py:1
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
test_SfmData.TestSfmData.tracks
tracks
Definition: test_SfmData.py:30
test_SfmData.TestSfmData.test_Balbianello
def test_Balbianello(self)
Definition: test_SfmData.py:86
gtsam::utils.test_case.GtsamTestCase
Definition: test_case.py:16
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::noiseModel::Isotropic::Sigma
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:625
gtsam::findExampleDataFile
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Definition: dataset.cpp:70
measurement
static Point2 measurement(323.0, 240.0)


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:16:00