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 Shonan Rotation Averaging CLI reads a *pose* graph, extracts the 10 rotation constraints, and runs the Shonan algorithm. 12 Author: Frank Dellaert 19 import matplotlib.pyplot
as plt
28 """ Estimate Poses from measurements, given rotations. From SfmProblem in shonan. 31 factors -- data structure with many BetweenFactorPose3 factors 32 rotations {Values} -- Estimated rotations 35 Values -- Estimated Poses 41 return rotations.atRot3(j)
if d == 3
else rotations.atRot2(j)
50 graph.add(0, I_d, np.zeros((d,)), model)
53 for factor
in factors:
55 i, j, Tij = keys[0], keys[1], factor.measured()
56 measured =
R(i).
rotate(Tij.translation())
57 graph.add(j, I_d, i, -I_d, measured, model)
60 translations = graph.optimize()
64 for j
in range(rotations.size()):
65 tj = translations.at(j)
66 result.insert(j,
pose(
R(j), tj))
72 """Run Shonan averaging and then recover translations linearly before saving result.""" 76 input_file = args.input_file
78 if args.named_dataset ==
"":
80 "You must either specify a named dataset or an input file")
83 if args.dimension == 2:
84 print(
"Running Shonan averaging for SO(2) on ", input_file)
86 if shonan.nrUnknowns() == 0:
87 raise ValueError(
"No 2D pose constraints found, try -d 3.")
88 initial = shonan.initializeRandomly()
89 rotations, _ = shonan.run(initial, 2, 10)
91 elif args.dimension == 3:
92 print(
"Running Shonan averaging for SO(3) on ", input_file)
94 if shonan.nrUnknowns() == 0:
95 raise ValueError(
"No 3D pose constraints found, try -d 2.")
96 initial = shonan.initializeRandomly()
97 rotations, _ = shonan.run(initial, 3, 10)
100 raise ValueError(
"Can only run SO(2) or SO(3) averaging")
102 print(
"Recovering translations")
105 print(
"Writing result to ", args.output_file)
108 plot.plot_trajectory(1, poses, scale=0.2)
109 plot.set_axes_equal(1)
113 if __name__ ==
"__main__":
114 parser = argparse.ArgumentParser()
115 parser.add_argument(
'-n',
'--named_dataset', type=str, default=
"pose3example-grid",
116 help=
'Find and read frome example dataset file')
117 parser.add_argument(
'-i',
'--input_file', type=str, default=
"",
118 help=
'Read pose constraints graph from the specified file')
119 parser.add_argument(
'-o',
'--output_file', type=str, default=
"shonan.g2o",
120 help=
'Write solution to the specified file')
121 parser.add_argument(
'-d',
'--dimension', type=int, default=3,
122 help=
'Optimize over 2D or 3D rotations')
123 parser.add_argument(
"-p",
"--plot", action=
"store_true", default=
True,
125 run(parser.parse_args())
void print(const Matrix &A, const string &s, ostream &stream)
void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, const std::string &filename)
This function writes a g2o file from NonlinearFactorGraph and a Values structure. ...
def estimate_poses_given_rot
BetweenFactorPose3s parse3DFactors(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex)
Rot2 R(Rot2::fromAngle(0.1))
BetweenFactorPose2s parse2DFactors(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex)
static shared_ptr Create(size_t dim)
Point3_ rotate(const Rot3_ &x, const Point3_ &p)
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Double_ range(const Point2_ &p, const Point2_ &q)