change to GTSAM timing
parent
1d81572894
commit
0b9758d88c
|
@ -24,6 +24,9 @@
|
||||||
#include <gtsam/slam/PriorFactor.h>
|
#include <gtsam/slam/PriorFactor.h>
|
||||||
#include <gtsam/slam/GeneralSFMFactor.h>
|
#include <gtsam/slam/GeneralSFMFactor.h>
|
||||||
#include <gtsam/slam/dataset.h> // for loading BAL datasets !
|
#include <gtsam/slam/dataset.h> // for loading BAL datasets !
|
||||||
|
|
||||||
|
#include <gtsam/base/timing.h>
|
||||||
|
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
@ -80,24 +83,17 @@ int main (int argc, char* argv[]) {
|
||||||
/** --------------- COMPARISON -----------------------**/
|
/** --------------- COMPARISON -----------------------**/
|
||||||
/** ----------------------------------------------------**/
|
/** ----------------------------------------------------**/
|
||||||
|
|
||||||
double t_COLAMD_ordering, t_METIS_ordering; //, t_NATURAL_ordering;
|
LevenbergMarquardtParams params_using_COLAMD, params_using_METIS;
|
||||||
LevenbergMarquardtParams params_using_COLAMD, params_using_METIS, params_using_NATURAL;
|
|
||||||
try {
|
try {
|
||||||
double tic_t = clock();
|
|
||||||
params_using_METIS.setVerbosity("ERROR");
|
params_using_METIS.setVerbosity("ERROR");
|
||||||
|
gttic_(METIS_ORDERING);
|
||||||
params_using_METIS.ordering = Ordering::Create(Ordering::METIS, graph);
|
params_using_METIS.ordering = Ordering::Create(Ordering::METIS, graph);
|
||||||
t_METIS_ordering = (clock() - tic_t)/CLOCKS_PER_SEC;
|
gttoc_(METIS_ORDERING);
|
||||||
|
|
||||||
tic_t = clock();
|
|
||||||
params_using_COLAMD.setVerbosity("ERROR");
|
params_using_COLAMD.setVerbosity("ERROR");
|
||||||
|
gttic_(COLAMD_ORDERING);
|
||||||
params_using_COLAMD.ordering = Ordering::Create(Ordering::COLAMD, graph);
|
params_using_COLAMD.ordering = Ordering::Create(Ordering::COLAMD, graph);
|
||||||
t_COLAMD_ordering = (clock() - tic_t)/CLOCKS_PER_SEC;
|
gttoc_(COLAMD_ORDERING);
|
||||||
|
|
||||||
// tic_t = clock();
|
|
||||||
// params_using_NATURAL.setVerbosity("ERROR");
|
|
||||||
// params_using_NATURAL.ordering = Ordering::Create(Ordering::NATURAL, graph);
|
|
||||||
// t_NATURAL_ordering = (clock() - tic_t)/CLOCKS_PER_SEC;
|
|
||||||
|
|
||||||
} catch (exception& e) {
|
} catch (exception& e) {
|
||||||
cout << e.what();
|
cout << e.what();
|
||||||
}
|
}
|
||||||
|
@ -108,49 +104,23 @@ int main (int argc, char* argv[]) {
|
||||||
<< "Problem here!!!" << endl;
|
<< "Problem here!!!" << endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* with METIS, optimize the graph and print the results */
|
/* Optimize the graph with METIS and COLAMD and time the results */
|
||||||
cout << "Optimize with METIS" << endl;
|
|
||||||
|
|
||||||
Values result_METIS;
|
Values result_METIS, result_COLAMD;
|
||||||
double t_METIS_solving;
|
|
||||||
try {
|
try {
|
||||||
double tic_t = clock();
|
gttic_(OPTIMIZE_WITH_METIS);
|
||||||
LevenbergMarquardtOptimizer lm_METIS(graph, initial, params_using_COLAMD);
|
LevenbergMarquardtOptimizer lm_METIS(graph, initial, params_using_METIS);
|
||||||
result_METIS = lm_METIS.optimize();
|
result_METIS = lm_METIS.optimize();
|
||||||
t_METIS_solving = (clock() - tic_t)/CLOCKS_PER_SEC;
|
gttoc_(OPTIMIZE_WITH_METIS);
|
||||||
} catch (exception& e) {
|
|
||||||
cout << e.what();
|
|
||||||
}
|
|
||||||
|
|
||||||
/* With COLAMD, optimize the graph and print the results */
|
gttic_(OPTIMIZE_WITH_COLAMD);
|
||||||
cout << "Optimize with COLAMD..." << endl;
|
|
||||||
|
|
||||||
Values result_COLAMD;
|
|
||||||
double t_COLAMD_solving;
|
|
||||||
try {
|
|
||||||
double tic_t = clock();
|
|
||||||
LevenbergMarquardtOptimizer lm_COLAMD(graph, initial, params_using_COLAMD);
|
LevenbergMarquardtOptimizer lm_COLAMD(graph, initial, params_using_COLAMD);
|
||||||
result_COLAMD = lm_COLAMD.optimize();
|
result_COLAMD = lm_COLAMD.optimize();
|
||||||
t_COLAMD_solving = (clock() - tic_t)/CLOCKS_PER_SEC;
|
gttoc_(OPTIMIZE_WITH_COLAMD);
|
||||||
} catch (exception& e) {
|
} catch (exception& e) {
|
||||||
cout << e.what();
|
cout << e.what();
|
||||||
}
|
}
|
||||||
|
|
||||||
// disable optimizer with NATURAL since it doesn't converge on large problem
|
|
||||||
/* Use Natural ordering and solve both respectively */
|
|
||||||
// cout << "Solving with natural ordering: " << endl;
|
|
||||||
|
|
||||||
// Values result_NATURAL;
|
|
||||||
// double t_NATURAL_solving;
|
|
||||||
// try {
|
|
||||||
// double tic_t = clock();
|
|
||||||
// LevenbergMarquardtOptimizer lm_NATURAL(graph, initial, params_using_NATURAL);
|
|
||||||
// result_NATURAL = lm_NATURAL.optimize();
|
|
||||||
// t_NATURAL_solving = (clock() - tic_t)/CLOCKS_PER_SEC;
|
|
||||||
// } catch (exception& e) {
|
|
||||||
// cout << e.what();
|
|
||||||
// }
|
|
||||||
|
|
||||||
cout << endl << endl;
|
cout << endl << endl;
|
||||||
|
|
||||||
{
|
{
|
||||||
|
@ -160,22 +130,21 @@ int main (int argc, char* argv[]) {
|
||||||
% mydata.number_tracks() % mydata.number_cameras() \
|
% mydata.number_tracks() % mydata.number_cameras() \
|
||||||
<< endl;
|
<< endl;
|
||||||
|
|
||||||
cout << "COLAMD: " << endl;
|
cout << "COLAMD final error: " << graph.error(result_COLAMD) << endl;
|
||||||
cout << "Ordering: " << t_COLAMD_ordering << "seconds" << endl;
|
cout << "METIS final error: " << graph.error(result_METIS) << endl;
|
||||||
cout << "Solving: " << t_COLAMD_solving << "seconds" << endl;
|
|
||||||
cout << "final error: " << graph.error(result_COLAMD) << endl;
|
|
||||||
|
|
||||||
cout << "METIS: " << endl;
|
tictoc_print_();
|
||||||
cout << "Ordering: " << t_METIS_ordering << "seconds" << endl;
|
|
||||||
cout << "Solving: " << t_METIS_solving << "seconds" << endl;
|
|
||||||
cout << "final error: " << graph.error(result_METIS) << endl;
|
|
||||||
|
|
||||||
// cout << "Natural: " << endl;
|
// cout << "COLAMD: " << endl;
|
||||||
// cout << "Ordering: " << t_NATURAL_ordering << "seconds" << endl;
|
// cout << "Ordering: " << t_COLAMD_ordering << "seconds" << endl;
|
||||||
// cout << "Solving: " << t_NATURAL_solving << "seconds" << endl;
|
// cout << "Solving: " << t_COLAMD_solving << "seconds" << endl;
|
||||||
// cout << "final error: " << graph.error(result_NATURAL) << endl;
|
|
||||||
|
// cout << "METIS: " << endl;
|
||||||
|
// cout << "Ordering: " << t_METIS_ordering << "seconds" << endl;
|
||||||
|
// cout << "Solving: " << t_METIS_solving << "seconds" << endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
Loading…
Reference in New Issue