Pose2SLAMExample.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 Simple robotics example using odometry measurements and bearing-range (laser) measurements
10 Author: Alex Cunningham (C++), Kevin Deng & Frank Dellaert (Python)
11 """
12 # pylint: disable=invalid-name, E1101
13 
14 from __future__ import print_function
15 
16 import math
17 
18 import numpy as np
19 
20 import gtsam
21 
22 import matplotlib.pyplot as plt
23 import gtsam.utils.plot as gtsam_plot
24 
25 
26 def vector3(x, y, z):
27  """Create 3d double numpy array."""
28  return np.array([x, y, z], dtype=float)
29 
30 # Create noise models
31 PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(vector3(0.3, 0.3, 0.1))
32 ODOMETRY_NOISE = gtsam.noiseModel.Diagonal.Sigmas(vector3(0.2, 0.2, 0.1))
33 
34 # 1. Create a factor graph container and add factors to it
36 
37 # 2a. Add a prior on the first pose, setting it to the origin
38 # A prior factor consists of a mean and a noise ODOMETRY_NOISE (covariance matrix)
39 graph.add(gtsam.PriorFactorPose2(1, gtsam.Pose2(0, 0, 0), PRIOR_NOISE))
40 
41 # 2b. Add odometry factors
42 # Create odometry (Between) factors between consecutive poses
43 graph.add(gtsam.BetweenFactorPose2(1, 2, gtsam.Pose2(2, 0, 0), ODOMETRY_NOISE))
44 graph.add(gtsam.BetweenFactorPose2(
45  2, 3, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))
46 graph.add(gtsam.BetweenFactorPose2(
47  3, 4, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))
48 graph.add(gtsam.BetweenFactorPose2(
49  4, 5, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))
50 
51 # 2c. Add the loop closure constraint
52 # This factor encodes the fact that we have returned to the same pose. In real
53 # systems, these constraints may be identified in many ways, such as appearance-based
54 # techniques with camera images. We will use another Between Factor to enforce this constraint:
55 graph.add(gtsam.BetweenFactorPose2(
56  5, 2, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))
57 print("\nFactor Graph:\n{}".format(graph)) # print
58 
59 # 3. Create the data structure to hold the initial_estimate estimate to the
60 # solution. For illustrative purposes, these have been deliberately set to incorrect values
61 initial_estimate = gtsam.Values()
62 initial_estimate.insert(1, gtsam.Pose2(0.5, 0.0, 0.2))
63 initial_estimate.insert(2, gtsam.Pose2(2.3, 0.1, -0.2))
64 initial_estimate.insert(3, gtsam.Pose2(4.1, 0.1, math.pi / 2))
65 initial_estimate.insert(4, gtsam.Pose2(4.0, 2.0, math.pi))
66 initial_estimate.insert(5, gtsam.Pose2(2.1, 2.1, -math.pi / 2))
67 print("\nInitial Estimate:\n{}".format(initial_estimate)) # print
68 
69 # 4. Optimize the initial values using a Gauss-Newton nonlinear optimizer
70 # The optimizer accepts an optional set of configuration parameters,
71 # controlling things like convergence criteria, the type of linear
72 # system solver to use, and the amount of information displayed during
73 # optimization. We will set a few parameters as a demonstration.
75 
76 # Stop iterating once the change in error between steps is less than this value
77 parameters.setRelativeErrorTol(1e-5)
78 # Do not perform more than N iteration steps
79 parameters.setMaxIterations(100)
80 # Create the optimizer ...
81 optimizer = gtsam.GaussNewtonOptimizer(graph, initial_estimate, parameters)
82 # ... and optimize
83 result = optimizer.optimize()
84 print("Final Result:\n{}".format(result))
85 
86 # 5. Calculate and print marginal covariances for all variables
87 marginals = gtsam.Marginals(graph, result)
88 for i in range(1, 6):
89  print("X{} covariance:\n{}\n".format(i, marginals.marginalCovariance(i)))
90 
91 fig = plt.figure(0)
92 for i in range(1, 6):
93  gtsam_plot.plot_pose2(0, result.atPose2(i), 0.5, marginals.marginalCovariance(i))
94 
95 plt.axis('equal')
96 plt.show()
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:27