timeShonanAveraging.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 #include "gtsam/base/Matrix.h"
21 #include "gtsam/base/Vector.h"
22 #include "gtsam/geometry/Point3.h"
23 #include "gtsam/geometry/Rot3.h"
24 #include <gtsam/base/timing.h>
26 
28 
29 #include <chrono>
30 #include <fstream>
31 #include <iostream>
32 #include <map>
33 
34 using namespace std;
35 using namespace gtsam;
36 
37 // save a single line of timing info to an output stream
38 void saveData(size_t p, double time1, double costP, double cost3, double time2,
39  double min_eigenvalue, double suBound, std::ostream* os) {
40  *os << static_cast<int>(p) << "\t" << time1 << "\t" << costP << "\t" << cost3
41  << "\t" << time2 << "\t" << min_eigenvalue << "\t" << suBound << endl;
42 }
43 
44 void checkR(const Matrix& R) {
45  Matrix R2 = R.transpose();
46  Matrix actual_R = R2 * R;
47  assert_equal(Rot3(), Rot3(actual_R));
48 }
49 
50 void saveResult(string name, const Values& values) {
51  ofstream myfile;
52  myfile.open("shonan_result_of_" + name + ".dat");
53  size_t nrSO3 = values.count<SO3>();
54  myfile << "#Type SO3 Number " << nrSO3 << "\n";
55  for (int i = 0; i < nrSO3; ++i) {
56  Matrix R = values.at<SO3>(i).matrix();
57  // Check if the result of R.Transpose*R satisfy orthogonal constraint
58  checkR(R);
59  myfile << i;
60  for (int m = 0; m < 3; ++m) {
61  for (int n = 0; n < 3; ++n) {
62  myfile << " " << R(m, n);
63  }
64  }
65  myfile << "\n";
66  }
67  myfile.close();
68  cout << "Saved shonan_result.dat file" << endl;
69 }
70 
71 void saveG2oResult(string name, const Values& values, std::map<Key, Pose3> poses) {
72  ofstream myfile;
73  myfile.open("shonan_result_of_" + name + ".g2o");
74  size_t nrSO3 = values.count<SO3>();
75  for (int i = 0; i < nrSO3; ++i) {
76  Matrix R = values.at<SO3>(i).matrix();
77  // Check if the result of R.Transpose*R satisfy orthogonal constraint
78  checkR(R);
79  myfile << "VERTEX_SE3:QUAT" << " ";
80  myfile << i << " ";
81  myfile << poses[i].x() << " " << poses[i].y() << " " << poses[i].z() << " ";
83  myfile << quaternion(3) << " " << quaternion(2) << " " << quaternion(1)
84  << " " << quaternion(0);
85  myfile << "\n";
86  }
87  myfile.close();
88  cout << "Saved shonan_result.g2o file" << endl;
89 }
90 
92  ofstream myfile;
93  myfile.open("shonan_result.dat");
94  size_t nrSOn = values.count<SOn>();
95  for (int i = 0; i < nrSOn; ++i) {
96  GTSAM_PRINT(values.at<SOn>(i));
97  Rot3 R = Rot3(values.at<SOn>(i).matrix());
98  float x = R.toQuaternion().x();
99  float y = R.toQuaternion().y();
100  float z = R.toQuaternion().z();
101  float w = R.toQuaternion().w();
102  myfile << "QuatSO3 " << i;
103  myfile << "QuatSO3 " << i << " " << w << " " << x << " " << y << " " << z << "\n";
104  myfile.close();
105  }
106 }
107 
108 int main(int argc, char* argv[]) {
109  // primitive argument parsing:
110  if (argc > 3) {
111  throw runtime_error("Usage: timeShonanAveraging [g2oFile]");
112  }
113 
114  string g2oFile;
115  try {
116  if (argc > 1)
117  g2oFile = argv[argc - 1];
118  else
119  g2oFile = findExampleDataFile("sphere2500");
120 
121  } catch (const exception& e) {
122  cerr << e.what() << '\n';
123  exit(1);
124  }
125 
126  // Create a csv output file
127  size_t pos1 = g2oFile.find("data/");
128  size_t pos2 = g2oFile.find(".g2o");
129  string name = g2oFile.substr(pos1 + 5, pos2 - pos1 - 5);
130  cout << name << endl;
131  ofstream csvFile("shonan_timing_of_" + name + ".csv");
132 
133  // Create Shonan averaging instance from the file.
134  // ShonanAveragingParameters parameters;
135  // double sigmaNoiseInRadians = 0 * M_PI / 180;
136  // parameters.setNoiseSigma(sigmaNoiseInRadians);
137  static const ShonanAveraging3 kShonan(g2oFile);
138 
139  // increase p value and try optimize using Shonan Algorithm. use chrono for
140  // timing
141  size_t pMin = 3;
142  Values Qstar;
143  Vector minEigenVector;
144  double CostP = 0, Cost3 = 0, lambdaMin = 0, suBound = 0;
145  cout << "(int)p" << "\t" << "time1" << "\t" << "costP" << "\t" << "cost3" << "\t"
146  << "time2" << "\t" << "MinEigenvalue" << "\t" << "SuBound" << endl;
147 
148  const Values randomRotations = kShonan.initializeRandomly();
149 
150  for (size_t p = pMin; p <= 7; p++) {
151  // Randomly initialize at lowest level, initialize by line search after that
152  const Values initial =
153  (p > pMin) ? kShonan.initializeWithDescent(p, Qstar, minEigenVector,
154  lambdaMin)
155  : ShonanAveraging3::LiftTo<Rot3>(pMin, randomRotations);
156  chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
157  // optimizing
158  const Values result = kShonan.tryOptimizingAt(p, initial);
159  chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
160  chrono::duration<double> timeUsed1 =
161  chrono::duration_cast<chrono::duration<double>>(t2 - t1);
162  lambdaMin = kShonan.computeMinEigenValue(result, &minEigenVector);
163  chrono::steady_clock::time_point t3 = chrono::steady_clock::now();
164  chrono::duration<double> timeUsed2 =
165  chrono::duration_cast<chrono::duration<double>>(t3 - t1);
166  Qstar = result;
167  CostP = kShonan.costAt(p, result);
168  const Values SO3Values = kShonan.roundSolution(result);
169  Cost3 = kShonan.cost(SO3Values);
170  suBound = (Cost3 - CostP) / CostP;
171 
172  saveData(p, timeUsed1.count(), CostP, Cost3, timeUsed2.count(),
173  lambdaMin, suBound, &cout);
174  saveData(p, timeUsed1.count(), CostP, Cost3, timeUsed2.count(),
175  lambdaMin, suBound, &csvFile);
176  }
177  saveResult(name, kShonan.roundSolution(Qstar));
178  // saveG2oResult(name, kShonan.roundSolution(Qstar), kShonan.Poses());
179  return 0;
180 }
Matrix3f m
double computeMinEigenValue(const Values &values, Vector *minEigenVector=nullptr) const
Scalar * y
double cost(const Values &values) const
EIGEN_DEVICE_FUNC CoeffReturnType x() const
EIGEN_DEVICE_FUNC CoeffReturnType y() const
void saveResultQuat(const Values &values)
int n
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Rot2 R(Rot2::fromAngle(0.1))
leaf::MyValues values
double costAt(size_t p, const Values &values) const
Definition: Half.h:150
const MatrixNN & matrix() const
Return matrix.
Definition: SOn.h:152
void quaternion(void)
EIGEN_DEVICE_FUNC CoeffReturnType w() const
EIGEN_DEVICE_FUNC CoeffReturnType z() const
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
Values initializeRandomly(std::mt19937 &rng) const
static const ShonanAveraging3 kShonan
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RowVector3d w
void saveG2oResult(string name, const Values &values, std::map< Key, Pose3 > poses)
size_t count() const
Definition: Values.h:398
traits
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Values roundSolution(const Values &values) const
#define GTSAM_PRINT(x)
Definition: Testable.h:41
ofstream os("timeSchurFactors.csv")
Values tryOptimizingAt(size_t p, const Values &initial) const
void saveResult(string name, const Values &values)
int main(int argc, char *argv[])
3D Point
float * p
void checkR(const Matrix &R)
Annotation for function names.
Definition: attr.h:36
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
void saveData(size_t p, double time1, double costP, double cost3, double time2, double min_eigenvalue, double suBound, std::ostream *os)
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
gtsam::Quaternion toQuaternion() const
Definition: Rot3M.cpp:233
Timing utilities.
Shonan Averaging algorithm.
Values initializeWithDescent(size_t p, const Values &values, const Vector &minEigenVector, double minEigenValue, double gradienTolerance=1e-2, double preconditionedGradNormTolerance=1e-4) const
3D rotation represented as a rotation matrix or quaternion
Vector quaternion() const
Definition: Rot3.cpp:231


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:00