2 GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, 3 Atlanta, Georgia 30332-0415 5 Authors: Frank Dellaert, et al. (see THANKS for the full author list) 7 See LICENSE for the license information 9 Simple robotics example using odometry measurements and bearing-range (laser) measurements 10 Author: Alex Cunningham (C++), Kevin Deng & Frank Dellaert (Python) 14 from __future__
import print_function
22 import matplotlib.pyplot
as plt
27 """Create 3d double numpy array.""" 28 return np.array([x, y, z], dtype=float)
39 graph.add(gtsam.PriorFactorPose2(1,
gtsam.Pose2(0, 0, 0), PRIOR_NOISE))
43 graph.add(gtsam.BetweenFactorPose2(1, 2,
gtsam.Pose2(2, 0, 0), ODOMETRY_NOISE))
44 graph.add(gtsam.BetweenFactorPose2(
45 2, 3,
gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))
46 graph.add(gtsam.BetweenFactorPose2(
47 3, 4,
gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))
48 graph.add(gtsam.BetweenFactorPose2(
49 4, 5,
gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))
55 graph.add(gtsam.BetweenFactorPose2(
56 5, 2,
gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))
57 print(
"\nFactor Graph:\n{}".format(graph))
62 initial_estimate.insert(1,
gtsam.Pose2(0.5, 0.0, 0.2))
63 initial_estimate.insert(2,
gtsam.Pose2(2.3, 0.1, -0.2))
64 initial_estimate.insert(3,
gtsam.Pose2(4.1, 0.1, math.pi / 2))
65 initial_estimate.insert(4,
gtsam.Pose2(4.0, 2.0, math.pi))
66 initial_estimate.insert(5,
gtsam.Pose2(2.1, 2.1, -math.pi / 2))
67 print(
"\nInitial Estimate:\n{}".format(initial_estimate))
77 parameters.setRelativeErrorTol(1e-5)
79 parameters.setMaxIterations(100)
83 result = optimizer.optimize()
84 print(
"Final Result:\n{}".format(result))
89 print(
"X{} covariance:\n{}\n".format(i, marginals.marginalCovariance(i)))
93 gtsam_plot.plot_pose2(0, result.atPose2(i), 0.5, marginals.marginalCovariance(i))
void print(const Matrix &A, const string &s, ostream &stream)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)