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 (size_t 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 (size_t 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.x() << " " << quaternion.y() << " " << quaternion.z()
84  << " " << quaternion.w();
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 (size_t i = 0; i < nrSOn; ++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
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  }
178  // saveG2oResult(name, kShonan.roundSolution(Qstar), kShonan.Poses());
179  return 0;
180 }
timing.h
Timing utilities.
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
name
Annotation for function names.
Definition: attr.h:51
Vector.h
typedef and functions to augment Eigen's VectorXd
ShonanAveraging.h
Shonan Averaging algorithm.
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
TestHarness.h
Matrix.h
typedef and functions to augment Eigen's MatrixXd
x
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
Definition: gnuplot_common_settings.hh:12
saveResultQuat
void saveResultQuat(const Values &values)
Definition: timeShonanAveraging.cpp:91
gtsam::ShonanAveraging::roundSolution
Values roundSolution(const Values &values) const
Definition: ShonanAveraging.cpp:302
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
Point3.h
3D Point
os
ofstream os("timeSchurFactors.csv")
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
result
Values result
Definition: OdometryOptimize.cpp:8
kShonan
static const ShonanAveraging3 kShonan
Definition: testShonanAveraging.cpp:46
gtsam::ShonanAveraging::initializeRandomly
Values initializeRandomly(std::mt19937 &rng) const
Definition: ShonanAveraging.cpp:859
Rot3.h
3D rotation represented as a rotation matrix or quaternion
quaternion
void quaternion(void)
Definition: geo_quaternion.cpp:46
n
int n
Definition: BiCGSTAB_simple.cpp:1
gtsam::ShonanAveraging::initializeWithDescent
Values initializeWithDescent(size_t p, const Values &values, const Vector &minEigenVector, double minEigenValue, double gradienTolerance=1e-2, double preconditionedGradNormTolerance=1e-4) const
Definition: ShonanAveraging.cpp:820
gtsam::SO::matrix
const MatrixNN & matrix() const
Return matrix.
Definition: SOn.h:157
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::ShonanAveraging::computeMinEigenValue
double computeMinEigenValue(const Values &values, Vector *minEigenVector=nullptr) const
Definition: ShonanAveraging.cpp:713
gtsam::ShonanAveraging3
Definition: ShonanAveraging.h:438
gtsam::Rot3::toQuaternion
gtsam::Quaternion toQuaternion() const
Definition: Rot3M.cpp:232
saveResult
void saveResult(string name, const Values &values)
Definition: timeShonanAveraging.cpp:50
GTSAM_PRINT
#define GTSAM_PRINT(x)
Definition: Testable.h:43
pybind_wrapper_test_script.z
z
Definition: pybind_wrapper_test_script.py:61
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
saveData
void saveData(size_t p, double time1, double costP, double cost3, double time2, double min_eigenvalue, double suBound, std::ostream *os)
Definition: timeShonanAveraging.cpp:38
saveG2oResult
void saveG2oResult(string name, const Values &values, std::map< Key, Pose3 > poses)
Definition: timeShonanAveraging.cpp:71
gtsam::Rot2::transpose
Matrix2 transpose() const
Definition: Rot2.cpp:92
main
int main(int argc, char *argv[])
Definition: timeShonanAveraging.cpp:108
y
Scalar * y
Definition: level1_cplx_impl.h:124
matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Definition: gtsam/3rdparty/Eigen/blas/common.h:110
gtsam::ShonanAveraging::costAt
double costAt(size_t p, const Values &values) const
Definition: ShonanAveraging.cpp:163
gtsam::HybridValues::at
Vector & at(Key j)
Definition: HybridValues.cpp:129
Eigen::Quaternion
The quaternion class used to represent 3D orientations and rotations.
Definition: ForwardDeclarations.h:293
so3::R2
SO3 R2
Definition: testShonanFactor.cpp:43
gtsam
traits
Definition: SFMdata.h:40
gtsam::Values
Definition: Values.h:65
checkR
void checkR(const Matrix &R)
Definition: timeShonanAveraging.cpp:44
std
Definition: BFloat16.h:88
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::SO< 3 >
initial
Definition: testScenarioRunner.cpp:148
gtsam::findExampleDataFile
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Definition: dataset.cpp:70
gtsam::ShonanAveraging::cost
double cost(const Values &values) const
Definition: ShonanAveraging.cpp:311
gtsam::ShonanAveraging::tryOptimizingAt
Values tryOptimizingAt(size_t p, const Values &initial) const
Definition: ShonanAveraging.cpp:190
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
R
Rot2 R(Rot2::fromAngle(0.1))


gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:42:28