2 GTSAM Copyright 2010, Georgia Tech Research Corporation, 3 Atlanta, Georgia 30332-0415 5 Authors: Frank Dellaert, et al. (see THANKS for the full author list) 7 See LICENSE for the license information 9 A visualSLAM example for the structure-from-motion problem on a simulated dataset 10 This version uses iSAM to solve the problem incrementally 13 from __future__
import print_function
18 from gtsam
import (Cal3_S2, GenericProjectionFactorCal3_S2,
19 NonlinearFactorGraph, NonlinearISAM, Pose3,
20 PriorFactorPoint3, PriorFactorPose3, Rot3,
21 PinholeCameraCal3_S2, Values, Point3)
26 A structure-from-motion example with landmarks 27 - The landmarks form a 10 meter cube 28 - The robot rotates around the landmarks, always facing towards the cube 32 K =
Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)
39 points = SFMdata.createPoints()
41 poses = SFMdata.createPoses(K)
49 initial_estimate =
Values()
52 for i, pose
in enumerate(poses):
55 for j, point
in enumerate(points):
56 measurement = camera.project(point)
58 measurement, camera_noise,
X(i),
L(j), K)
59 graph.push_back(factor)
62 noise =
Pose3(r=Rot3.Rodrigues(-0.1, 0.2, 0.25),
63 t=Point3(0.05, -0.10, 0.20))
64 initial_xi = pose.compose(noise)
67 initial_estimate.insert(
X(i), initial_xi)
76 np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1]))
78 graph.push_back(factor)
83 graph.push_back(factor)
86 noise = np.array([-0.25, 0.20, 0.15])
87 for j, point
in enumerate(points):
89 initial_lj = points[j] + noise
90 initial_estimate.insert(
L(j), initial_lj)
93 isam.update(graph, initial_estimate)
94 current_estimate = isam.estimate()
96 print(
'Frame {}:'.format(i))
97 current_estimate.print_(
'Current estimate: ')
101 initial_estimate.clear()
104 if __name__ ==
'__main__':
void print(const Matrix &A, const string &s, ostream &stream)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)