2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, 3 Atlanta, Georgia 30332-0415 6 See LICENSE for the license information 8 Unit tests for testing dataset access. 9 Author: Frank Dellaert (Python: Sushmita Warrier) 13 from __future__
import print_function
19 from gtsam
import Point2, Point3, SfmData, SfmTrack
24 """Tests for SfmData and SfmTrack modules.""" 27 """Initialize SfmData and SfmTrack""" 33 """Test functions in SfmTrack""" 45 self.
tracks.addMeasurement(i1, uv_i1)
46 self.
tracks.addMeasurement(i2, uv_i2)
49 self.assertEqual(self.
tracks.numberMeasurements(), 2)
53 self.assertEqual(cam_idx, i1)
54 np.testing.assert_array_almost_equal(
60 """Test functions in SfmData""" 63 uv_i1 =
Point2(21.23, 45.64)
66 uv_i2 =
Point2(45.7, 45.64)
67 uv_i3 =
Point2(68.35, 45.64)
70 measurements = [(i1, uv_i1), (i2, uv_i2), (i3, uv_i3)]
73 track2.addMeasurement(i1, uv_i1)
74 track2.addMeasurement(i2, uv_i2)
75 track2.addMeasurement(i3, uv_i3)
77 self.
data.addTrack(track2)
80 self.assertEqual(self.
data.numberTracks(), 2)
84 self.assertEqual(cam_idx, i1)
87 """ Check that we can successfully read a bundler file and create a 92 sfm_data = SfmData.FromBundlerFile(filename)
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())
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]
112 graph = sfm_data.sfmFactorGraph(model)
113 self.assertEqual(1419, graph.size())
117 self.assertEqual(549, values.size())
120 if __name__ ==
'__main__':
SfmData stores a bunch of SfmTracks.
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Values initialCamerasAndPointsEstimate(const SfmData &db)
This function creates initial values for cameras and points from db.
static Point2 measurement(323.0, 240.0)
static const Point3 point3(0.08, 0.08, 0.0)
def test_Balbianello(self)
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)