2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, 3 Atlanta, Georgia 30332-0415 6 See LICENSE for the license information 9 Author: Frank Dellaert & Duy Nguyen Ta (Python) 17 from gtsam
import symbol
25 options = generator.Options()
26 options.triangle =
False 27 options.nrCameras = 10
29 [data, truth] = generator.generate_data(options)
31 measurementNoiseSigma = 1.0
33 poseNoiseSigmas = np.array([0.001, 0.001, 0.001, 0.1, 0.1, 0.1])
38 measurementNoise = Isotropic.Sigma(2, measurementNoiseSigma)
39 for i
in range(
len(data.Z)):
40 for k
in range(
len(data.Z[i])):
42 graph.add(gtsam.GenericProjectionFactorCal3_S2(
43 data.Z[i][k], measurementNoise,
46 posePriorNoise = Diagonal.Sigmas(poseNoiseSigmas)
47 graph.add(gtsam.PriorFactorPose3(
X(0),
48 truth.cameras[0].
pose(), posePriorNoise))
49 pointPriorNoise = Isotropic.Sigma(3, pointNoiseSigma)
50 graph.add(gtsam.PriorFactorPoint3(
P(0),
51 truth.points[0], pointPriorNoise))
55 for i
in range(
len(truth.cameras)):
56 pose_i = truth.cameras[i].
pose()
57 initialEstimate.insert(
X(i), pose_i)
58 for j
in range(
len(truth.points)):
59 point_j = truth.points[j]
60 initialEstimate.insert(
P(j), point_j)
66 result = optimizer.values()
70 marginals.marginalCovariance(
P(0))
71 marginals.marginalCovariance(
X(0))
74 for i
in range(
len(truth.cameras)):
75 pose_i = result.atPose3(
X(i))
78 for j
in range(
len(truth.points)):
79 point_j = result.atPoint3(
P(j))
82 if __name__ ==
"__main__":
def test_SFMExample(self)
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
All noise models live in the noiseModel namespace.