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)
37 axes = fig.add_subplot(projection=
'3d')
46 gtsam_plot.plot_3d_points(fignum, result,
'rx')
50 while result.exists(
X(i)):
51 pose_i = result.atPose3(
X(i))
52 gtsam_plot.plot_pose3(fignum, pose_i, 10)
56 axes.set_xlim3d(-40, 40)
57 axes.set_ylim3d(-40, 40)
58 axes.set_zlim3d(-40, 40)
73 points = SFMdata.createPoints()
76 poses = SFMdata.createPoses(K)
86 parameters.setRelinearizeThreshold(0.01)
87 parameters.relinearizeSkip = 1
95 for i, pose
in enumerate(poses):
98 for j, point
in enumerate(points):
100 measurement = camera.project(point)
101 graph.push_back(gtsam.GenericProjectionFactorCal3_S2(
102 measurement, measurement_noise,
X(i),
L(j), K))
116 [0.1, 0.1, 0.1, 0.3, 0.3, 0.3]))
117 graph.push_back(gtsam.PriorFactorPose3(
X(0), poses[0], pose_noise))
121 graph.push_back(gtsam.PriorFactorPoint3(
122 L(0), points[0], point_noise))
126 for j, point
in enumerate(points):
128 point[0]-0.25, point[1]+0.20, point[2]+0.15))
131 isam.update(graph, initial_estimate)
136 current_estimate = isam.calculateEstimate()
137 print(
"****************************************************")
138 print(
"Frame", i,
":")
139 for j
in range(i + 1):
140 print(
X(j),
":", current_estimate.atPose3(
X(j)))
143 print(
L(j),
":", current_estimate.atPoint3(
L(j)))
149 initial_estimate.clear()
155 if __name__ ==
'__main__':
void print(const Matrix &A, const string &s, ostream &stream)
static Rot3 Rodrigues(const Vector3 &w)
The most common 5DOF 3D->2D calibration.
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Double_ range(const Point2_ &p, const Point2_ &q)
def visual_ISAM2_plot(result)
size_t len(handle h)
Get the length of a Python object.
def visual_ISAM2_example()
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)