PlanarSLAMExample.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 numpy as np
17 
18 import gtsam
19 from gtsam.symbol_shorthand import X, L
20 
21 # Create noise models
22 PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.1]))
23 ODOMETRY_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.2, 0.2, 0.1]))
24 MEASUREMENT_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.2]))
25 
26 # Create an empty nonlinear factor graph
28 
29 # Create the keys corresponding to unknown variables in the factor graph
30 X1 = X(1)
31 X2 = X(2)
32 X3 = X(3)
33 L1 = L(4)
34 L2 = L(5)
35 
36 # Add a prior on pose X1 at the origin. A prior factor consists of a mean and a noise model
37 graph.add(gtsam.PriorFactorPose2(X1, gtsam.Pose2(0.0, 0.0, 0.0), PRIOR_NOISE))
38 
39 # Add odometry factors between X1,X2 and X2,X3, respectively
40 graph.add(gtsam.BetweenFactorPose2(
41  X1, X2, gtsam.Pose2(2.0, 0.0, 0.0), ODOMETRY_NOISE))
42 graph.add(gtsam.BetweenFactorPose2(
43  X2, X3, gtsam.Pose2(2.0, 0.0, 0.0), ODOMETRY_NOISE))
44 
45 # Add Range-Bearing measurements to two different landmarks L1 and L2
46 graph.add(gtsam.BearingRangeFactor2D(
47  X1, L1, gtsam.Rot2.fromDegrees(45), np.sqrt(4.0+4.0), MEASUREMENT_NOISE))
48 graph.add(gtsam.BearingRangeFactor2D(
49  X2, L1, gtsam.Rot2.fromDegrees(90), 2.0, MEASUREMENT_NOISE))
50 graph.add(gtsam.BearingRangeFactor2D(
51  X3, L2, gtsam.Rot2.fromDegrees(90), 2.0, MEASUREMENT_NOISE))
52 
53 # Print graph
54 print("Factor Graph:\n{}".format(graph))
55 
56 # Create (deliberately inaccurate) initial estimate
57 initial_estimate = gtsam.Values()
58 initial_estimate.insert(X1, gtsam.Pose2(-0.25, 0.20, 0.15))
59 initial_estimate.insert(X2, gtsam.Pose2(2.30, 0.10, -0.20))
60 initial_estimate.insert(X3, gtsam.Pose2(4.10, 0.10, 0.10))
61 initial_estimate.insert(L1, gtsam.Point2(1.80, 2.10))
62 initial_estimate.insert(L2, gtsam.Point2(4.10, 1.80))
63 
64 # Print
65 print("Initial Estimate:\n{}".format(initial_estimate))
66 
67 # Optimize using Levenberg-Marquardt optimization. The optimizer
68 # accepts an optional set of configuration parameters, controlling
69 # things like convergence criteria, the type of linear system solver
70 # to use, and the amount of information displayed during optimization.
71 # Here we will use the default set of parameters. See the
72 # documentation for the full set of parameters.
74 optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial_estimate, params)
75 result = optimizer.optimize()
76 print("\nFinal Result:\n{}".format(result))
77 
78 # Calculate and print marginal covariances for all variables
79 marginals = gtsam.Marginals(graph, result)
80 for (key, str) in [(X1, "X1"), (X2, "X2"), (X3, "X3"), (L1, "L1"), (L2, "L2")]:
81  print("{} covariance:\n{}\n".format(str, marginals.marginalCovariance(key)))
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Vector2 Point2
Definition: Point2.h:27
MatrixXd L
Definition: LLT_example.cpp:6
static Rot2 fromDegrees(double theta)
Named constructor from angle in degrees.
Definition: Rot2.h:63
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270
#define X
Definition: icosphere.cpp:20


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