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 gtsam
19 import gtsam.utils.plot as gtsam_plot
20 import matplotlib.pyplot as plt
21 
22 
23 def main():
24  """Main runner."""
25  # Create noise models
26  PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(gtsam.Point3(0.3, 0.3, 0.1))
27  ODOMETRY_NOISE = gtsam.noiseModel.Diagonal.Sigmas(
28  gtsam.Point3(0.2, 0.2, 0.1))
29 
30  # 1. Create a factor graph container and add factors to it
32 
33  # 2a. Add a prior on the first pose, setting it to the origin
34  # A prior factor consists of a mean and a noise ODOMETRY_NOISE (covariance matrix)
35  graph.add(gtsam.PriorFactorPose2(1, gtsam.Pose2(0, 0, 0), PRIOR_NOISE))
36 
37  # 2b. Add odometry factors
38  # Create odometry (Between) factors between consecutive poses
39  graph.add(
40  gtsam.BetweenFactorPose2(1, 2, gtsam.Pose2(2, 0, 0), ODOMETRY_NOISE))
41  graph.add(
42  gtsam.BetweenFactorPose2(2, 3, gtsam.Pose2(2, 0, math.pi / 2),
43  ODOMETRY_NOISE))
44  graph.add(
45  gtsam.BetweenFactorPose2(3, 4, gtsam.Pose2(2, 0, math.pi / 2),
46  ODOMETRY_NOISE))
47  graph.add(
48  gtsam.BetweenFactorPose2(4, 5, gtsam.Pose2(2, 0, math.pi / 2),
49  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(
56  gtsam.BetweenFactorPose2(5, 2, gtsam.Pose2(2, 0, math.pi / 2),
57  ODOMETRY_NOISE))
58  print("\nFactor Graph:\n{}".format(graph)) # print
59 
60  # 3. Create the data structure to hold the initial_estimate estimate to the
61  # solution. For illustrative purposes, these have been deliberately set to incorrect values
62  initial_estimate = gtsam.Values()
63  initial_estimate.insert(1, gtsam.Pose2(0.5, 0.0, 0.2))
64  initial_estimate.insert(2, gtsam.Pose2(2.3, 0.1, -0.2))
65  initial_estimate.insert(3, gtsam.Pose2(4.1, 0.1, math.pi / 2))
66  initial_estimate.insert(4, gtsam.Pose2(4.0, 2.0, math.pi))
67  initial_estimate.insert(5, gtsam.Pose2(2.1, 2.1, -math.pi / 2))
68  print("\nInitial Estimate:\n{}".format(initial_estimate)) # print
69 
70  # 4. Optimize the initial values using a Gauss-Newton nonlinear optimizer
71  # The optimizer accepts an optional set of configuration parameters,
72  # controlling things like convergence criteria, the type of linear
73  # system solver to use, and the amount of information displayed during
74  # optimization. We will set a few parameters as a demonstration.
75  parameters = gtsam.GaussNewtonParams()
76 
77  # Stop iterating once the change in error between steps is less than this value
78  parameters.setRelativeErrorTol(1e-5)
79  # Do not perform more than N iteration steps
80  parameters.setMaxIterations(100)
81  # Create the optimizer ...
82  optimizer = gtsam.GaussNewtonOptimizer(graph, initial_estimate, parameters)
83  # ... and optimize
84  result = optimizer.optimize()
85  print("Final Result:\n{}".format(result))
86 
87  # 5. Calculate and print marginal covariances for all variables
88  marginals = gtsam.Marginals(graph, result)
89  for i in range(1, 6):
90  print("X{} covariance:\n{}\n".format(i,
91  marginals.marginalCovariance(i)))
92 
93  for i in range(1, 6):
94  gtsam_plot.plot_pose2(0, result.atPose2(i), 0.5,
95  marginals.marginalCovariance(i))
96 
97  plt.axis('equal')
98  plt.show()
99 
100 
101 if __name__ == "__main__":
102  main()
format
std::string format(const std::string &str, const std::vector< std::string > &find, const std::vector< std::string > &replace)
Definition: openglsupport.cpp:226
gtsam::GaussNewtonOptimizer
Definition: GaussNewtonOptimizer.h:38
gtsam::Marginals
Definition: Marginals.h:32
gtsam::noiseModel::Diagonal::Sigmas
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:292
gtsam::range
Double_ range(const Point2_ &p, const Point2_ &q)
Definition: slam/expressions.h:30
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
gtsam::GaussNewtonParams
Definition: GaussNewtonOptimizer.h:30
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam.examples.Pose2SLAMExample.main
def main()
Definition: Pose2SLAMExample.py:23
gtsam::Values
Definition: Values.h:65
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::utils.plot
Definition: plot.py:1
gtsam::Pose2
Definition: Pose2.h:39


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:12:45