Pose3SLAMExample_g2o.py
Go to the documentation of this file.
1 """
2  * @file Pose3SLAMExample_initializePose3.cpp
3  * @brief A 3D Pose SLAM example that reads input from g2o, and initializes the
4  * Pose3 using InitializePose3
5  * @date Jan 17, 2019
6  * @author Vikrant Shah based on CPP example by Luca Carlone
7 """
8 # pylint: disable=invalid-name, E1101
9 
10 from __future__ import print_function
11 
12 import argparse
13 
14 import gtsam
15 import matplotlib.pyplot as plt
16 import numpy as np
17 from gtsam.utils import plot
18 from mpl_toolkits.mplot3d import Axes3D
19 
20 
21 def vector6(x, y, z, a, b, c):
22  """Create 6d double numpy array."""
23  return np.array([x, y, z, a, b, c], dtype=float)
24 
25 
26 def main():
27  """Main runner."""
28 
29  parser = argparse.ArgumentParser(
30  description="A 3D Pose SLAM example that reads input from g2o, and "
31  "initializes Pose3")
32  parser.add_argument('-i', '--input', help='input file g2o format')
33  parser.add_argument(
34  '-o',
35  '--output',
36  help="the path to the output file with optimized graph")
37  parser.add_argument("-p",
38  "--plot",
39  action="store_true",
40  help="Flag to plot results")
41  args = parser.parse_args()
42 
43  g2oFile = gtsam.findExampleDataFile("pose3example.txt") if args.input is None \
44  else args.input
45 
46  is3D = True
47  graph, initial = gtsam.readG2o(g2oFile, is3D)
48 
49  # Add Prior on the first key
51  vector6(1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4))
52 
53  print("Adding prior to g2o file ")
54  firstKey = initial.keys()[0]
55  graph.add(gtsam.PriorFactorPose3(firstKey, gtsam.Pose3(), priorModel))
56 
57  params = gtsam.GaussNewtonParams()
58  params.setVerbosity(
59  "Termination") # this will show info about stopping conds
60  optimizer = gtsam.GaussNewtonOptimizer(graph, initial, params)
61  result = optimizer.optimize()
62  print("Optimization complete")
63 
64  print("initial error = ", graph.error(initial))
65  print("final error = ", graph.error(result))
66 
67  if args.output is None:
68  print("Final Result:\n{}".format(result))
69  else:
70  outputFile = args.output
71  print("Writing results to file: ", outputFile)
72  graphNoKernel, _ = gtsam.readG2o(g2oFile, is3D)
73  gtsam.writeG2o(graphNoKernel, result, outputFile)
74  print("Done!")
75 
76  if args.plot:
77  resultPoses = gtsam.utilities.allPose3s(result)
78  for i in range(resultPoses.size()):
79  plot.plot_pose3(1, resultPoses.atPose3(i))
80  plt.show()
81 
82 
83 if __name__ == "__main__":
84  main()
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, const std::string &filename)
This function writes a g2o file from NonlinearFactorGraph and a Values structure. ...
Definition: dataset.cpp:636
Values allPose3s(const Values &values)
Extract all Pose3 values.
GraphAndValues readG2o(const std::string &g2oFile, const bool is3D, KernelFunctionType kernelFunctionType)
This function parses a g2o file and stores the measurements into a NonlinearFactorGraph and the initi...
Definition: dataset.cpp:621
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Definition: dataset.cpp:70
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)
static shared_ptr Variances(const Vector &variances, bool smart=true)
Definition: NoiseModel.cpp:258


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:35:15