|
| 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 | +See LICENSE for the license information |
| 7 | +
|
| 8 | +Simple robotics example using odometry measurements and bearing-range (laser) measurements. |
| 9 | +From borglab/gtsam python/gtsam/examples/PlanarSLAMExample.py (GTSAM 4.2.0). |
| 10 | +
|
| 11 | +Run inside container: python3 /examples/PlanarSLAMExample.py |
| 12 | +""" |
| 13 | +# pylint: disable=invalid-name, E1101 |
| 14 | + |
| 15 | +from __future__ import print_function |
| 16 | + |
| 17 | +import sys |
| 18 | +import gtsam |
| 19 | +import numpy as np |
| 20 | +from gtsam.symbol_shorthand import L, X |
| 21 | + |
| 22 | +# Create noise models |
| 23 | +PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) |
| 24 | +ODOMETRY_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) |
| 25 | +MEASUREMENT_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.2])) |
| 26 | + |
| 27 | + |
| 28 | +def main(): |
| 29 | + """Main runner.""" |
| 30 | + # Create an empty nonlinear factor graph |
| 31 | + graph = gtsam.NonlinearFactorGraph() |
| 32 | + |
| 33 | + # Create the keys corresponding to unknown variables in the factor graph |
| 34 | + x1, x2, x3 = X(1), X(2), X(3) |
| 35 | + l1, l2 = L(4), L(5) |
| 36 | + |
| 37 | + # Add a prior on pose X1 at the origin |
| 38 | + graph.add( |
| 39 | + gtsam.PriorFactorPose2(x1, gtsam.Pose2(0.0, 0.0, 0.0), PRIOR_NOISE) |
| 40 | + ) |
| 41 | + |
| 42 | + # Add odometry factors between X1,X2 and X2,X3 |
| 43 | + graph.add( |
| 44 | + gtsam.BetweenFactorPose2(x1, x2, gtsam.Pose2(2.0, 0.0, 0.0), ODOMETRY_NOISE) |
| 45 | + ) |
| 46 | + graph.add( |
| 47 | + gtsam.BetweenFactorPose2(x2, x3, gtsam.Pose2(2.0, 0.0, 0.0), ODOMETRY_NOISE) |
| 48 | + ) |
| 49 | + |
| 50 | + # Add Range-Bearing measurements to two different landmarks L1 and L2 |
| 51 | + graph.add( |
| 52 | + gtsam.BearingRangeFactor2D( |
| 53 | + x1, l1, gtsam.Rot2.fromDegrees(45), np.sqrt(4.0 + 4.0), MEASUREMENT_NOISE |
| 54 | + ) |
| 55 | + ) |
| 56 | + graph.add( |
| 57 | + gtsam.BearingRangeFactor2D(x2, l1, gtsam.Rot2.fromDegrees(90), 2.0, MEASUREMENT_NOISE) |
| 58 | + ) |
| 59 | + graph.add( |
| 60 | + gtsam.BearingRangeFactor2D(x3, l2, gtsam.Rot2.fromDegrees(90), 2.0, MEASUREMENT_NOISE) |
| 61 | + ) |
| 62 | + |
| 63 | + print("Factor Graph:\n{}".format(graph)) |
| 64 | + |
| 65 | + # Create (deliberately inaccurate) initial estimate |
| 66 | + initial_estimate = gtsam.Values() |
| 67 | + initial_estimate.insert(x1, gtsam.Pose2(-0.25, 0.20, 0.15)) |
| 68 | + initial_estimate.insert(x2, gtsam.Pose2(2.30, 0.10, -0.20)) |
| 69 | + initial_estimate.insert(x3, gtsam.Pose2(4.10, 0.10, 0.10)) |
| 70 | + initial_estimate.insert(l1, gtsam.Point2(1.80, 2.10)) |
| 71 | + initial_estimate.insert(l2, gtsam.Point2(4.10, 1.80)) |
| 72 | + |
| 73 | + print("Initial Estimate:\n{}".format(initial_estimate)) |
| 74 | + |
| 75 | + # Optimize using Levenberg-Marquardt |
| 76 | + params = gtsam.LevenbergMarquardtParams() |
| 77 | + optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial_estimate, params) |
| 78 | + result = optimizer.optimize() |
| 79 | + print("\nFinal Result:\n{}".format(result)) |
| 80 | + |
| 81 | + # Calculate and print marginal covariances |
| 82 | + marginals = gtsam.Marginals(graph, result) |
| 83 | + for (key, label) in [(x1, "X1"), (x2, "X2"), (x3, "X3"), (l1, "L1"), (l2, "L2")]: |
| 84 | + print("{} covariance:\n{}\n".format(label, marginals.marginalCovariance(key))) |
| 85 | + |
| 86 | + # Validation: expect result size and non-NaN covariances |
| 87 | + assert result.size() == 5, "Expected 5 values in result" |
| 88 | + _ = marginals.marginalCovariance(x1) # will raise if invalid |
| 89 | + print("VALIDATION OK") |
| 90 | + return 0 |
| 91 | + |
| 92 | +if __name__ == "__main__": |
| 93 | + sys.exit(main()) |
0 commit comments