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 Pose SLAM example using iSAM2 in the 2D plane. 10 Author: Jerred Chen, Yusuf Ali 12 - VisualISAM2Example by: Duy-Nguyen Ta (C++), Frank Dellaert (Python) 13 - Pose2SLAMExample by: Alex Cunningham (C++), Kevin Deng & Frank Dellaert (Python) 18 import matplotlib.pyplot
as plt
26 """Print and plot incremental progress of the robot for 2D Pose SLAM using iSAM2.""" 29 print(
"*"*50 + f
"\nInference after State {key+1}:\n")
30 print(current_estimate)
41 while current_estimate.exists(i):
42 gtsam_plot.plot_pose2(0, current_estimate.atPose2(i), 0.5, marginals.marginalCovariance(i))
51 key: int, xy_tol=0.6, theta_tol=17) -> int:
52 """Simple brute force approach which iterates through previous states 53 and checks for loop closure. 56 odom: Vector representing noisy odometry (x, y, theta) measurement in the body frame. 57 current_estimate: The current estimates computed by iSAM2. 58 key: Key corresponding to the current state estimate of the robot. 59 xy_tol: Optional argument for the x-y measurement tolerance, in meters. 60 theta_tol: Optional argument for the theta measurement tolerance, in degrees. 62 k: The key of the state which is helping add the loop closure constraint. 63 If loop closure is not found, then None is returned. 66 prev_est = current_estimate.atPose2(key+1)
67 rotated_odom = prev_est.rotation().
matrix() @ odom[:2]
68 curr_xy = np.array([prev_est.x() + rotated_odom[0],
69 prev_est.y() + rotated_odom[1]])
70 curr_theta = prev_est.theta() + odom[2]
71 for k
in range(1, key+1):
72 pose_xy = np.array([current_estimate.atPose2(k).
x(),
73 current_estimate.atPose2(k).
y()])
74 pose_theta = current_estimate.atPose2(k).theta()
75 if (
abs(pose_xy - curr_xy) <= xy_tol).
all()
and \
76 (
abs(pose_theta - curr_theta) <= theta_tol*np.pi/180):
80 """Perform 2D SLAM given the ground truth changes in pose as well as 81 simple loop closure detection.""" 91 odometry_xy_sigma = 0.2
94 odometry_theta_sigma = 5
101 prior_theta_sigma*np.pi/180]))
104 odometry_theta_sigma*np.pi/180]))
113 parameters.setRelinearizeThreshold(0.1)
114 parameters.relinearizeSkip = 1
118 true_odometry = [(2, 0, 0),
125 odometry_measurements = [np.random.multivariate_normal(true_odom, ODOMETRY_NOISE.covariance())
126 for true_odom
in true_odometry]
130 graph.push_back(gtsam.PriorFactorPose2(1,
gtsam.Pose2(0, 0, 0), PRIOR_NOISE))
131 initial_estimate.insert(1,
gtsam.Pose2(0.5, 0.0, 0.2))
134 current_estimate = initial_estimate
139 noisy_odom_x, noisy_odom_y, noisy_odom_theta = odometry_measurements[i]
147 graph.push_back(gtsam.BetweenFactorPose2(i + 1, loop,
148 gtsam.Pose2(noisy_odom_x, noisy_odom_y, noisy_odom_theta), ODOMETRY_NOISE))
150 graph.push_back(gtsam.BetweenFactorPose2(i + 1, i + 2,
151 gtsam.Pose2(noisy_odom_x, noisy_odom_y, noisy_odom_theta), ODOMETRY_NOISE))
157 initial_estimate.insert(i + 2, computed_estimate)
160 isam.update(graph, initial_estimate)
161 current_estimate = isam.calculateEstimate()
165 initial_estimate.clear()
170 for i
in range(1,
len(true_odometry)+1):
171 print(f
"X{i} covariance:\n{marginals.marginalCovariance(i)}\n")
177 if __name__ ==
"__main__":
void print(const Matrix &A, const string &s, ostream &stream)
static const Eigen::internal::all_t all
def Pose2SLAM_ISAM2_example()
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Double_ range(const Point2_ &p, const Point2_ &q)
Expression< T > compose(const Expression< T > &t1, const Expression< T > &t2)
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
size_t len(handle h)
Get the length of a Python object.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
def determine_loop_closure