2 * @file Pose3SLAMExample_initializePose3.cpp
3 * @brief A 3D Pose SLAM example that reads input from g2o, and initializes the
4 * Pose3 using InitializePose3
6 * @author Vikrant Shah based on CPP example by Luca Carlone
10 from __future__
import print_function
15 import matplotlib.pyplot
as plt
18 from mpl_toolkits.mplot3d
import Axes3D
22 """Create 6d double numpy array."""
23 return np.array([x, y, z, a, b, c], dtype=float)
29 parser = argparse.ArgumentParser(
30 description=
"A 3D Pose SLAM example that reads input from g2o, and "
32 parser.add_argument(
'-i',
'--input', help=
'input file g2o format')
36 help=
"the path to the output file with optimized graph")
37 parser.add_argument(
"-p",
40 help=
"Flag to plot results")
41 args = parser.parse_args()
51 vector6(1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4))
53 print(
"Adding prior to g2o file ")
54 firstKey = initial.keys()[0]
55 graph.add(gtsam.PriorFactorPose3(firstKey,
gtsam.Pose3(), priorModel))
61 result = optimizer.optimize()
62 print(
"Optimization complete")
64 print(
"initial error = ", graph.error(initial))
65 print(
"final error = ", graph.error(result))
67 if args.output
is None:
70 outputFile = args.output
71 print(
"Writing results to file: ", outputFile)
78 for i
in range(resultPoses.size()):
79 plot.plot_pose3(1, resultPoses.atPose3(i))
83 if __name__ ==
"__main__":