Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_ in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
|
|
|
/* ----------------------------------------------------------------------------
|
|
|
|
|
|
|
|
* GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
|
|
|
|
* Atlanta, Georgia 30332-0415
|
|
|
|
* All Rights Reserved
|
|
|
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
|
|
|
|
|
|
|
* See LICENSE for the license information
|
|
|
|
|
|
|
|
* -------------------------------------------------------------------------- */
|
|
|
|
|
|
|
|
/**
|
|
|
|
* @file testShonanAveraging.cpp
|
|
|
|
* @date September 2019
|
|
|
|
* @author Jing Wu
|
|
|
|
* @author Frank Dellaert
|
|
|
|
* @brief Timing script for Shonan Averaging algorithm
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "gtsam/base/Matrix.h"
|
|
|
|
#include "gtsam/base/Vector.h"
|
|
|
|
#include "gtsam/geometry/Point3.h"
|
|
|
|
#include "gtsam/geometry/Rot3.h"
|
|
|
|
#include <gtsam/base/timing.h>
|
|
|
|
#include <gtsam/sfm/ShonanAveraging.h>
|
|
|
|
|
|
|
|
#include <CppUnitLite/TestHarness.h>
|
|
|
|
|
|
|
|
#include <chrono>
|
|
|
|
#include <fstream>
|
|
|
|
#include <iostream>
|
|
|
|
#include <map>
|
|
|
|
|
|
|
|
using namespace std;
|
|
|
|
using namespace gtsam;
|
|
|
|
|
|
|
|
// save a single line of timing info to an output stream
|
|
|
|
void saveData(size_t p, double time1, double costP, double cost3, double time2,
|
|
|
|
double min_eigenvalue, double suBound, std::ostream* os) {
|
2020-08-21 23:01:28 +08:00
|
|
|
*os << static_cast<int>(p) << "\t" << time1 << "\t" << costP << "\t" << cost3
|
|
|
|
<< "\t" << time2 << "\t" << min_eigenvalue << "\t" << suBound << endl;
|
Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_ in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
void checkR(const Matrix& R) {
|
|
|
|
Matrix R2 = R.transpose();
|
|
|
|
Matrix actual_R = R2 * R;
|
2020-08-21 23:01:28 +08:00
|
|
|
assert_equal(Rot3(), Rot3(actual_R));
|
Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_ in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
void saveResult(string name, const Values& values) {
|
|
|
|
ofstream myfile;
|
|
|
|
myfile.open("shonan_result_of_" + name + ".dat");
|
|
|
|
size_t nrSO3 = values.count<SO3>();
|
|
|
|
myfile << "#Type SO3 Number " << nrSO3 << "\n";
|
2021-06-15 04:25:15 +08:00
|
|
|
for (size_t i = 0; i < nrSO3; ++i) {
|
Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_ in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
|
|
|
Matrix R = values.at<SO3>(i).matrix();
|
|
|
|
// Check if the result of R.Transpose*R satisfy orthogonal constraint
|
|
|
|
checkR(R);
|
|
|
|
myfile << i;
|
|
|
|
for (int m = 0; m < 3; ++m) {
|
|
|
|
for (int n = 0; n < 3; ++n) {
|
|
|
|
myfile << " " << R(m, n);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
myfile << "\n";
|
|
|
|
}
|
|
|
|
myfile.close();
|
|
|
|
cout << "Saved shonan_result.dat file" << endl;
|
|
|
|
}
|
|
|
|
|
|
|
|
void saveG2oResult(string name, const Values& values, std::map<Key, Pose3> poses) {
|
|
|
|
ofstream myfile;
|
|
|
|
myfile.open("shonan_result_of_" + name + ".g2o");
|
|
|
|
size_t nrSO3 = values.count<SO3>();
|
2021-06-15 04:25:15 +08:00
|
|
|
for (size_t i = 0; i < nrSO3; ++i) {
|
Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_ in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
|
|
|
Matrix R = values.at<SO3>(i).matrix();
|
|
|
|
// Check if the result of R.Transpose*R satisfy orthogonal constraint
|
|
|
|
checkR(R);
|
|
|
|
myfile << "VERTEX_SE3:QUAT" << " ";
|
|
|
|
myfile << i << " ";
|
|
|
|
myfile << poses[i].x() << " " << poses[i].y() << " " << poses[i].z() << " ";
|
2022-06-08 16:42:50 +08:00
|
|
|
Quaternion quaternion = Rot3(R).toQuaternion();
|
|
|
|
myfile << quaternion.x() << " " << quaternion.y() << " " << quaternion.z()
|
|
|
|
<< " " << quaternion.w();
|
Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_ in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
|
|
|
myfile << "\n";
|
|
|
|
}
|
|
|
|
myfile.close();
|
|
|
|
cout << "Saved shonan_result.g2o file" << endl;
|
|
|
|
}
|
|
|
|
|
|
|
|
void saveResultQuat(const Values& values) {
|
|
|
|
ofstream myfile;
|
|
|
|
myfile.open("shonan_result.dat");
|
|
|
|
size_t nrSOn = values.count<SOn>();
|
2021-06-15 04:25:15 +08:00
|
|
|
for (size_t i = 0; i < nrSOn; ++i) {
|
Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_ in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
|
|
|
GTSAM_PRINT(values.at<SOn>(i));
|
|
|
|
Rot3 R = Rot3(values.at<SOn>(i).matrix());
|
|
|
|
float x = R.toQuaternion().x();
|
|
|
|
float y = R.toQuaternion().y();
|
|
|
|
float z = R.toQuaternion().z();
|
|
|
|
float w = R.toQuaternion().w();
|
|
|
|
myfile << "QuatSO3 " << i;
|
|
|
|
myfile << "QuatSO3 " << i << " " << w << " " << x << " " << y << " " << z << "\n";
|
|
|
|
myfile.close();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
int main(int argc, char* argv[]) {
|
|
|
|
// primitive argument parsing:
|
|
|
|
if (argc > 3) {
|
2020-08-21 23:01:28 +08:00
|
|
|
throw runtime_error("Usage: timeShonanAveraging [g2oFile]");
|
Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_ in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
string g2oFile;
|
|
|
|
try {
|
2020-08-21 23:01:28 +08:00
|
|
|
if (argc > 1)
|
|
|
|
g2oFile = argv[argc - 1];
|
|
|
|
else
|
|
|
|
g2oFile = findExampleDataFile("sphere2500");
|
Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_ in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
|
|
|
|
|
|
|
} catch (const exception& e) {
|
2020-08-21 23:01:28 +08:00
|
|
|
cerr << e.what() << '\n';
|
|
|
|
exit(1);
|
Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_ in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
// Create a csv output file
|
|
|
|
size_t pos1 = g2oFile.find("data/");
|
|
|
|
size_t pos2 = g2oFile.find(".g2o");
|
|
|
|
string name = g2oFile.substr(pos1 + 5, pos2 - pos1 - 5);
|
|
|
|
cout << name << endl;
|
|
|
|
ofstream csvFile("shonan_timing_of_" + name + ".csv");
|
|
|
|
|
|
|
|
// Create Shonan averaging instance from the file.
|
|
|
|
// ShonanAveragingParameters parameters;
|
|
|
|
// double sigmaNoiseInRadians = 0 * M_PI / 180;
|
|
|
|
// parameters.setNoiseSigma(sigmaNoiseInRadians);
|
|
|
|
static const ShonanAveraging3 kShonan(g2oFile);
|
|
|
|
|
|
|
|
// increase p value and try optimize using Shonan Algorithm. use chrono for
|
|
|
|
// timing
|
|
|
|
size_t pMin = 3;
|
|
|
|
Values Qstar;
|
|
|
|
Vector minEigenVector;
|
|
|
|
double CostP = 0, Cost3 = 0, lambdaMin = 0, suBound = 0;
|
|
|
|
cout << "(int)p" << "\t" << "time1" << "\t" << "costP" << "\t" << "cost3" << "\t"
|
|
|
|
<< "time2" << "\t" << "MinEigenvalue" << "\t" << "SuBound" << endl;
|
|
|
|
|
2020-08-21 23:01:28 +08:00
|
|
|
const Values randomRotations = kShonan.initializeRandomly();
|
Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_ in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
|
|
|
|
2020-08-21 23:01:28 +08:00
|
|
|
for (size_t p = pMin; p <= 7; p++) {
|
Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_ in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
|
|
|
// Randomly initialize at lowest level, initialize by line search after that
|
|
|
|
const Values initial =
|
|
|
|
(p > pMin) ? kShonan.initializeWithDescent(p, Qstar, minEigenVector,
|
|
|
|
lambdaMin)
|
2020-08-21 23:01:28 +08:00
|
|
|
: ShonanAveraging3::LiftTo<Rot3>(pMin, randomRotations);
|
Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_ in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
2020-08-17 19:43:10 +08:00
|
|
|
chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
|
|
|
|
// optimizing
|
|
|
|
const Values result = kShonan.tryOptimizingAt(p, initial);
|
|
|
|
chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
|
|
|
|
chrono::duration<double> timeUsed1 =
|
|
|
|
chrono::duration_cast<chrono::duration<double>>(t2 - t1);
|
|
|
|
lambdaMin = kShonan.computeMinEigenValue(result, &minEigenVector);
|
|
|
|
chrono::steady_clock::time_point t3 = chrono::steady_clock::now();
|
|
|
|
chrono::duration<double> timeUsed2 =
|
|
|
|
chrono::duration_cast<chrono::duration<double>>(t3 - t1);
|
|
|
|
Qstar = result;
|
|
|
|
CostP = kShonan.costAt(p, result);
|
|
|
|
const Values SO3Values = kShonan.roundSolution(result);
|
|
|
|
Cost3 = kShonan.cost(SO3Values);
|
|
|
|
suBound = (Cost3 - CostP) / CostP;
|
|
|
|
|
|
|
|
saveData(p, timeUsed1.count(), CostP, Cost3, timeUsed2.count(),
|
|
|
|
lambdaMin, suBound, &cout);
|
|
|
|
saveData(p, timeUsed1.count(), CostP, Cost3, timeUsed2.count(),
|
|
|
|
lambdaMin, suBound, &csvFile);
|
|
|
|
}
|
|
|
|
saveResult(name, kShonan.roundSolution(Qstar));
|
|
|
|
// saveG2oResult(name, kShonan.roundSolution(Qstar), kShonan.Poses());
|
|
|
|
return 0;
|
|
|
|
}
|