Pose2ISAM2Example.py
Go to the documentation of this file.
1 """
2 GTSAM Copyright 2010-2018, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
4 All Rights Reserved
5 Authors: Frank Dellaert, et al. (see THANKS for the full author list)
6 
7 See LICENSE for the license information
8 
9 Pose SLAM example using iSAM2 in the 2D plane.
10 Author: Jerred Chen, Yusuf Ali
11 Modeled after:
12  - VisualISAM2Example by: Duy-Nguyen Ta (C++), Frank Dellaert (Python)
13  - Pose2SLAMExample by: Alex Cunningham (C++), Kevin Deng & Frank Dellaert (Python)
14 """
15 
16 import math
17 
18 import matplotlib.pyplot as plt
19 import numpy as np
20 
21 import gtsam
22 import gtsam.utils.plot as gtsam_plot
23 
24 def report_on_progress(graph: gtsam.NonlinearFactorGraph, current_estimate: gtsam.Values,
25  key: int):
26  """Print and plot incremental progress of the robot for 2D Pose SLAM using iSAM2."""
27 
28  # Print the current estimates computed using iSAM2.
29  print("*"*50 + f"\nInference after State {key+1}:\n")
30  print(current_estimate)
31 
32  # Compute the marginals for all states in the graph.
33  marginals = gtsam.Marginals(graph, current_estimate)
34 
35  # Plot the newly updated iSAM2 inference.
36  fig = plt.figure(0)
37  axes = fig.gca()
38  plt.cla()
39 
40  i = 1
41  while current_estimate.exists(i):
42  gtsam_plot.plot_pose2(0, current_estimate.atPose2(i), 0.5, marginals.marginalCovariance(i))
43  i += 1
44 
45  plt.axis('equal')
46  axes.set_xlim(-1, 5)
47  axes.set_ylim(-1, 3)
48  plt.pause(1)
49 
50 def determine_loop_closure(odom: np.ndarray, current_estimate: gtsam.Values,
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.
54 
55  Args:
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.
61  Returns:
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.
64  """
65  if current_estimate:
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):
77  return k
78 
80  """Perform 2D SLAM given the ground truth changes in pose as well as
81  simple loop closure detection."""
82  plt.ion()
83 
84  # Declare the 2D translational standard deviations of the prior factor's Gaussian model, in meters.
85  prior_xy_sigma = 0.3
86 
87  # Declare the 2D rotational standard deviation of the prior factor's Gaussian model, in degrees.
88  prior_theta_sigma = 5
89 
90  # Declare the 2D translational standard deviations of the odometry factor's Gaussian model, in meters.
91  odometry_xy_sigma = 0.2
92 
93  # Declare the 2D rotational standard deviation of the odometry factor's Gaussian model, in degrees.
94  odometry_theta_sigma = 5
95 
96  # Although this example only uses linear measurements and Gaussian noise models, it is important
97  # to note that iSAM2 can be utilized to its full potential during nonlinear optimization. This example
98  # simply showcases how iSAM2 may be applied to a Pose2 SLAM problem.
99  PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([prior_xy_sigma,
100  prior_xy_sigma,
101  prior_theta_sigma*np.pi/180]))
102  ODOMETRY_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([odometry_xy_sigma,
103  odometry_xy_sigma,
104  odometry_theta_sigma*np.pi/180]))
105 
106  # Create a Nonlinear factor graph as well as the data structure to hold state estimates.
108  initial_estimate = gtsam.Values()
109 
110  # Create iSAM2 parameters which can adjust the threshold necessary to force relinearization and how many
111  # update calls are required to perform the relinearization.
112  parameters = gtsam.ISAM2Params()
113  parameters.setRelinearizeThreshold(0.1)
114  parameters.relinearizeSkip = 1
115  isam = gtsam.ISAM2(parameters)
116 
117  # Create the ground truth odometry measurements of the robot during the trajectory.
118  true_odometry = [(2, 0, 0),
119  (2, 0, math.pi/2),
120  (2, 0, math.pi/2),
121  (2, 0, math.pi/2),
122  (2, 0, math.pi/2)]
123 
124  # Corrupt the odometry measurements with gaussian noise to create noisy odometry measurements.
125  odometry_measurements = [np.random.multivariate_normal(true_odom, ODOMETRY_NOISE.covariance())
126  for true_odom in true_odometry]
127 
128  # Add the prior factor to the factor graph, and poorly initialize the prior pose to demonstrate
129  # iSAM2 incremental optimization.
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))
132 
133  # Initialize the current estimate which is used during the incremental inference loop.
134  current_estimate = initial_estimate
135 
136  for i in range(len(true_odometry)):
137 
138  # Obtain the noisy odometry that is received by the robot and corrupted by gaussian noise.
139  noisy_odom_x, noisy_odom_y, noisy_odom_theta = odometry_measurements[i]
140 
141  # Determine if there is loop closure based on the odometry measurement and the previous estimate of the state.
142  loop = determine_loop_closure(odometry_measurements[i], current_estimate, i, xy_tol=0.8, theta_tol=25)
143 
144  # Add a binary factor in between two existing states if loop closure is detected.
145  # Otherwise, add a binary factor between a newly observed state and the previous state.
146  if loop:
147  graph.push_back(gtsam.BetweenFactorPose2(i + 1, loop,
148  gtsam.Pose2(noisy_odom_x, noisy_odom_y, noisy_odom_theta), ODOMETRY_NOISE))
149  else:
150  graph.push_back(gtsam.BetweenFactorPose2(i + 1, i + 2,
151  gtsam.Pose2(noisy_odom_x, noisy_odom_y, noisy_odom_theta), ODOMETRY_NOISE))
152 
153  # Compute and insert the initialization estimate for the current pose using the noisy odometry measurement.
154  computed_estimate = current_estimate.atPose2(i + 1).compose(gtsam.Pose2(noisy_odom_x,
155  noisy_odom_y,
156  noisy_odom_theta))
157  initial_estimate.insert(i + 2, computed_estimate)
158 
159  # Perform incremental update to iSAM2's internal Bayes tree, optimizing only the affected variables.
160  isam.update(graph, initial_estimate)
161  current_estimate = isam.calculateEstimate()
162 
163  # Report all current state estimates from the iSAM2 optimzation.
164  report_on_progress(graph, current_estimate, i)
165  initial_estimate.clear()
166 
167  # Print the final covariance matrix for each pose after completing inference on the trajectory.
168  marginals = gtsam.Marginals(graph, current_estimate)
169  i = 1
170  for i in range(1, len(true_odometry)+1):
171  print(f"X{i} covariance:\n{marginals.marginalCovariance(i)}\n")
172 
173  plt.ioff()
174  plt.show()
175 
176 
177 if __name__ == "__main__":
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
static const Eigen::internal::all_t all
Scalar * y
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270
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.
Definition: pytypes.h:2244
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
#define abs(x)
Definition: datatypes.h:17


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:35:14