2 GTSAM Copyright 2010-2018, 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 An example of running visual SLAM using iSAM2. 10 Author: Duy-Nguyen Ta (C++), Frank Dellaert (Python) 14 from __future__
import print_function
18 import matplotlib.pyplot
as plt
22 from mpl_toolkits.mplot3d
import Axes3D
27 VisualISAMPlot plots current state of ISAM2 object 29 Based on MATLAB version by: Duy Nguyen Ta and Frank Dellaert 35 fig = plt.figure(fignum)
36 axes = fig.gca(projection=
'3d')
43 gtsam_plot.plot_3d_points(fignum, result,
'rx')
47 while result.exists(
X(i)):
48 pose_i = result.atPose3(
X(i))
49 gtsam_plot.plot_pose3(fignum, pose_i, 10)
53 axes.set_xlim3d(-40, 40)
54 axes.set_ylim3d(-40, 40)
55 axes.set_zlim3d(-40, 40)
70 points = SFMdata.createPoints()
73 poses = SFMdata.createPoses(K)
83 parameters.setRelinearizeThreshold(0.01)
84 parameters.setRelinearizeSkip(1)
92 for i, pose
in enumerate(poses):
95 for j, point
in enumerate(points):
97 measurement = camera.project(point)
98 graph.push_back(gtsam.GenericProjectionFactorCal3_S2(
99 measurement, measurement_noise,
X(i),
L(j), K))
113 [0.1, 0.1, 0.1, 0.3, 0.3, 0.3]))
114 graph.push_back(gtsam.PriorFactorPose3(
X(0), poses[0], pose_noise))
118 graph.push_back(gtsam.PriorFactorPoint3(
119 L(0), points[0], point_noise))
123 for j, point
in enumerate(points):
125 point[0]-0.25, point[1]+0.20, point[2]+0.15))
128 isam.update(graph, initial_estimate)
133 current_estimate = isam.calculateEstimate()
134 print(
"****************************************************")
135 print(
"Frame", i,
":")
136 for j
in range(i + 1):
137 print(
X(j),
":", current_estimate.atPose3(
X(j)))
139 for j
in range(
len(points)):
140 print(
L(j),
":", current_estimate.atPoint3(
L(j)))
146 initial_estimate.clear()
152 if __name__ ==
'__main__':
void print(const Matrix &A, const string &s, ostream &stream)
static Rot3 Rodrigues(const Vector3 &w)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
def visual_ISAM2_plot(result)
def visual_ISAM2_example()
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)