OdometryExample.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 robot motion example, with prior and two odometry measurements
10 Author: Frank Dellaert
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 
20 import matplotlib.pyplot as plt
21 import gtsam.utils.plot as gtsam_plot
22 
23 # Create noise models
24 ODOMETRY_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.2, 0.2, 0.1]))
25 PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.1]))
26 
27 # Create an empty nonlinear factor graph
29 
30 # Add a prior on the first pose, setting it to the origin
31 # A prior factor consists of a mean and a noise model (covariance matrix)
32 priorMean = gtsam.Pose2(0.0, 0.0, 0.0) # prior at origin
33 graph.add(gtsam.PriorFactorPose2(1, priorMean, PRIOR_NOISE))
34 
35 # Add odometry factors
36 odometry = gtsam.Pose2(2.0, 0.0, 0.0)
37 # For simplicity, we will use the same noise model for each odometry factor
38 # Create odometry (Between) factors between consecutive poses
39 graph.add(gtsam.BetweenFactorPose2(1, 2, odometry, ODOMETRY_NOISE))
40 graph.add(gtsam.BetweenFactorPose2(2, 3, odometry, ODOMETRY_NOISE))
41 print("\nFactor Graph:\n{}".format(graph))
42 
43 # Create the data structure to hold the initialEstimate estimate to the solution
44 # For illustrative purposes, these have been deliberately set to incorrect values
45 initial = gtsam.Values()
46 initial.insert(1, gtsam.Pose2(0.5, 0.0, 0.2))
47 initial.insert(2, gtsam.Pose2(2.3, 0.1, -0.2))
48 initial.insert(3, gtsam.Pose2(4.1, 0.1, 0.1))
49 print("\nInitial Estimate:\n{}".format(initial))
50 
51 # optimize using Levenberg-Marquardt optimization
53 optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params)
54 result = optimizer.optimize()
55 print("\nFinal Result:\n{}".format(result))
56 
57 # 5. Calculate and print marginal covariances for all variables
58 marginals = gtsam.Marginals(graph, result)
59 for i in range(1, 4):
60  print("X{} covariance:\n{}\n".format(i, marginals.marginalCovariance(i)))
61 
62 fig = plt.figure(0)
63 for i in range(1, 4):
64  gtsam_plot.plot_pose2(0, result.atPose2(i), 0.5, marginals.marginalCovariance(i))
65 plt.axis('equal')
66 plt.show()
67 
68 
69 
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:05