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
20 import matplotlib.pyplot
as plt
35 graph.add(gtsam.PriorFactorPose2(1,
gtsam.Pose2(0, 0, 0), PRIOR_NOISE))
40 gtsam.BetweenFactorPose2(1, 2,
gtsam.Pose2(2, 0, 0), ODOMETRY_NOISE))
42 gtsam.BetweenFactorPose2(2, 3,
gtsam.Pose2(2, 0, math.pi / 2),
45 gtsam.BetweenFactorPose2(3, 4,
gtsam.Pose2(2, 0, math.pi / 2),
48 gtsam.BetweenFactorPose2(4, 5,
gtsam.Pose2(2, 0, math.pi / 2),
56 gtsam.BetweenFactorPose2(5, 2,
gtsam.Pose2(2, 0, math.pi / 2),
63 initial_estimate.insert(1,
gtsam.Pose2(0.5, 0.0, 0.2))
64 initial_estimate.insert(2,
gtsam.Pose2(2.3, 0.1, -0.2))
65 initial_estimate.insert(3,
gtsam.Pose2(4.1, 0.1, math.pi / 2))
66 initial_estimate.insert(4,
gtsam.Pose2(4.0, 2.0, math.pi))
67 initial_estimate.insert(5,
gtsam.Pose2(2.1, 2.1, -math.pi / 2))
68 print(
"\nInitial Estimate:\n{}".
format(initial_estimate))
78 parameters.setRelativeErrorTol(1e-5)
80 parameters.setMaxIterations(100)
84 result = optimizer.optimize()
91 marginals.marginalCovariance(i)))
94 gtsam_plot.plot_pose2(0, result.atPose2(i), 0.5,
95 marginals.marginalCovariance(i))
101 if __name__ ==
"__main__":
void print(const Matrix &A, const string &s, ostream &stream)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Double_ range(const Point2_ &p, const Point2_ &q)
std::string format(const std::string &str, const std::vector< std::string > &find, const std::vector< std::string > &replace)