test_LocalizationExample.py
Go to the documentation of this file.
1 """
2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
4 All Rights Reserved
5 
6 See LICENSE for the license information
7 
8 Localization unit tests.
9 Author: Frank Dellaert & Duy Nguyen Ta (Python)
10 """
11 import unittest
12 
13 import numpy as np
14 
15 import gtsam
16 from gtsam.utils.test_case import GtsamTestCase
17 
18 
20 
22  # Create the graph (defined in pose2SLAM.h, derived from
23  # NonlinearFactorGraph)
25 
26  # Add two odometry factors
27  # create a measurement for both factors (the same in this case)
28  odometry = gtsam.Pose2(2.0, 0.0, 0.0)
29  odometryNoise = gtsam.noiseModel.Diagonal.Sigmas(
30  np.array([0.2, 0.2, 0.1])) # 20cm std on x,y, 0.1 rad on theta
31  graph.add(gtsam.BetweenFactorPose2(0, 1, odometry, odometryNoise))
32  graph.add(gtsam.BetweenFactorPose2(1, 2, odometry, odometryNoise))
33 
34  # Add three "GPS" measurements
35  # We use Pose2 Priors here with high variance on theta
36  groundTruth = gtsam.Values()
37  groundTruth.insert(0, gtsam.Pose2(0.0, 0.0, 0.0))
38  groundTruth.insert(1, gtsam.Pose2(2.0, 0.0, 0.0))
39  groundTruth.insert(2, gtsam.Pose2(4.0, 0.0, 0.0))
40  model = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.1, 10.]))
41  for i in range(3):
42  graph.add(gtsam.PriorFactorPose2(i, groundTruth.atPose2(i), model))
43 
44  # Initialize to noisy points
45  initialEstimate = gtsam.Values()
46  initialEstimate.insert(0, gtsam.Pose2(0.5, 0.0, 0.2))
47  initialEstimate.insert(1, gtsam.Pose2(2.3, 0.1, -0.2))
48  initialEstimate.insert(2, gtsam.Pose2(4.1, 0.1, 0.1))
49 
50  # Optimize using Levenberg-Marquardt optimization with an ordering from
51  # colamd
52  optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initialEstimate)
53  result = optimizer.optimizeSafely()
54 
55  # Plot Covariance Ellipses
56  marginals = gtsam.Marginals(graph, result)
57  P = [None] * result.size()
58  for i in range(0, result.size()):
59  pose_i = result.atPose2(i)
60  self.gtsamAssertEquals(pose_i, groundTruth.atPose2(i), 1e-4)
61  P[i] = marginals.marginalCovariance(i)
62 
63 if __name__ == "__main__":
64  unittest.main()
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Definition: test_case.py:18
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:03