Added stats mode in SolverComparer
parent
1a41b9f4a2
commit
431c9b1987
|
@ -9,18 +9,22 @@
|
||||||
* -------------------------------------------------------------------------- */
|
* -------------------------------------------------------------------------- */
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @file timeIncremental.cpp
|
* @file SolverComparer.cpp
|
||||||
* @brief Incremental and batch solving, timing, and accuracy comparisons
|
* @brief Incremental and batch solving, timing, and accuracy comparisons
|
||||||
* @author Richard Roberts
|
* @author Richard Roberts
|
||||||
|
* @date August, 2013
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam/base/timing.h>
|
#include <gtsam/base/timing.h>
|
||||||
|
#include <gtsam/base/treeTraversal-inst.h>
|
||||||
#include <gtsam/slam/dataset.h>
|
#include <gtsam/slam/dataset.h>
|
||||||
#include <gtsam/geometry/Pose2.h>
|
#include <gtsam/geometry/Pose2.h>
|
||||||
#include <gtsam/slam/PriorFactor.h>
|
#include <gtsam/slam/PriorFactor.h>
|
||||||
#include <gtsam/slam/BetweenFactor.h>
|
#include <gtsam/slam/BetweenFactor.h>
|
||||||
#include <gtsam/slam/BearingRangeFactor.h>
|
#include <gtsam/slam/BearingRangeFactor.h>
|
||||||
#include <gtsam/inference/Symbol.h>
|
#include <gtsam/inference/Symbol.h>
|
||||||
|
#include <gtsam/linear/GaussianJunctionTree.h>
|
||||||
|
#include <gtsam/linear/GaussianEliminationTree.h>
|
||||||
#include <gtsam/nonlinear/ISAM2.h>
|
#include <gtsam/nonlinear/ISAM2.h>
|
||||||
#include <gtsam/nonlinear/GaussNewtonOptimizer.h>
|
#include <gtsam/nonlinear/GaussNewtonOptimizer.h>
|
||||||
#include <gtsam/nonlinear/Marginals.h>
|
#include <gtsam/nonlinear/Marginals.h>
|
||||||
|
@ -94,6 +98,7 @@ bool incremental;
|
||||||
bool batch;
|
bool batch;
|
||||||
bool compare;
|
bool compare;
|
||||||
bool perturb;
|
bool perturb;
|
||||||
|
bool stats;
|
||||||
double perturbationNoise;
|
double perturbationNoise;
|
||||||
string compareFile1, compareFile2;
|
string compareFile1, compareFile2;
|
||||||
|
|
||||||
|
@ -105,6 +110,7 @@ void runIncremental();
|
||||||
void runBatch();
|
void runBatch();
|
||||||
void runCompare();
|
void runCompare();
|
||||||
void runPerturb();
|
void runPerturb();
|
||||||
|
void runStats();
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
int main(int argc, char *argv[]) {
|
int main(int argc, char *argv[]) {
|
||||||
|
@ -123,6 +129,7 @@ int main(int argc, char *argv[]) {
|
||||||
("batch", "Run in batch mode, requires an initialization from --read-solution")
|
("batch", "Run in batch mode, requires an initialization from --read-solution")
|
||||||
("compare", po::value<vector<string> >()->multitoken(), "Compare two solution files")
|
("compare", po::value<vector<string> >()->multitoken(), "Compare two solution files")
|
||||||
("perturb", po::value<double>(&perturbationNoise), "Perturb a solution file with the specified noise")
|
("perturb", po::value<double>(&perturbationNoise), "Perturb a solution file with the specified noise")
|
||||||
|
("stats", "Gather factorization statistics about the dataset, writes text-file histograms")
|
||||||
;
|
;
|
||||||
po::variables_map vm;
|
po::variables_map vm;
|
||||||
po::store(po::command_line_parser(argc, argv).options(desc).run(), vm);
|
po::store(po::command_line_parser(argc, argv).options(desc).run(), vm);
|
||||||
|
@ -131,7 +138,9 @@ int main(int argc, char *argv[]) {
|
||||||
batch = (vm.count("batch") > 0);
|
batch = (vm.count("batch") > 0);
|
||||||
compare = (vm.count("compare") > 0);
|
compare = (vm.count("compare") > 0);
|
||||||
perturb = (vm.count("perturb") > 0);
|
perturb = (vm.count("perturb") > 0);
|
||||||
incremental = (vm.count("incremental") > 0 || (!batch && !compare && !perturb));
|
stats = (vm.count("stats") > 0);
|
||||||
|
const int modesSpecified = int(batch) + int(compare) + int(perturb) + int(stats);
|
||||||
|
incremental = (vm.count("incremental") > 0 || modesSpecified == 0);
|
||||||
if(compare) {
|
if(compare) {
|
||||||
const vector<string>& compareFiles = vm["compare"].as<vector<string> >();
|
const vector<string>& compareFiles = vm["compare"].as<vector<string> >();
|
||||||
if(compareFiles.size() != 2) {
|
if(compareFiles.size() != 2) {
|
||||||
|
@ -142,15 +151,15 @@ int main(int argc, char *argv[]) {
|
||||||
compareFile2 = compareFiles[1];
|
compareFile2 = compareFiles[1];
|
||||||
}
|
}
|
||||||
|
|
||||||
if((batch && incremental) || (batch && compare) || (incremental && compare)) {
|
if(modesSpecified > 1) {
|
||||||
cout << "Only one of --incremental, --batch, and --compare may be specified\n" << desc << endl;
|
cout << "Only one of --incremental, --batch, --compare, --perturb, and --stats may be specified\n" << desc << endl;
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
if((incremental || batch) && datasetName.empty()) {
|
if((incremental || batch) && datasetName.empty()) {
|
||||||
cout << "In incremental and batch modes, a dataset must be specified\n" << desc << endl;
|
cout << "In incremental and batch modes, a dataset must be specified\n" << desc << endl;
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
if(!(incremental || batch) && !datasetName.empty()) {
|
if(!(incremental || batch || stats) && !datasetName.empty()) {
|
||||||
cout << "A dataset may only be specified in incremental or batch modes\n" << desc << endl;
|
cout << "A dataset may only be specified in incremental or batch modes\n" << desc << endl;
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
|
@ -162,6 +171,10 @@ int main(int argc, char *argv[]) {
|
||||||
cout << "In perturb mode, specify input and output files\n" << desc << endl;
|
cout << "In perturb mode, specify input and output files\n" << desc << endl;
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
|
if(stats && (datasetName.empty() || inputFile.empty())) {
|
||||||
|
cout << "In stats mode, specify dataset and input file\n" << desc << endl;
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
// Read input file
|
// Read input file
|
||||||
if(!inputFile.empty())
|
if(!inputFile.empty())
|
||||||
|
@ -210,6 +223,8 @@ int main(int argc, char *argv[]) {
|
||||||
runCompare();
|
runCompare();
|
||||||
else if(perturb)
|
else if(perturb)
|
||||||
runPerturb();
|
runPerturb();
|
||||||
|
else if(stats)
|
||||||
|
runStats();
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -548,3 +563,28 @@ void runPerturb()
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
void runStats()
|
||||||
|
{
|
||||||
|
cout << "Gathering statistics..." << endl;
|
||||||
|
GaussianFactorGraph linear = *datasetMeasurements.linearize(initial);
|
||||||
|
GaussianJunctionTree jt(GaussianEliminationTree(linear, Ordering::COLAMD(linear)));
|
||||||
|
treeTraversal::ForestStatistics statistics = treeTraversal::GatherStatistics(jt);
|
||||||
|
|
||||||
|
ofstream file;
|
||||||
|
|
||||||
|
cout << "Writing SolverComparer_Stats_problemSizeHistogram.txt..." << endl;
|
||||||
|
file.open("SolverComparer_Stats_problemSizeHistogram.txt");
|
||||||
|
treeTraversal::ForestStatistics::Write(file, statistics.problemSizeHistogram);
|
||||||
|
file.close();
|
||||||
|
|
||||||
|
cout << "Writing SolverComparer_Stats_numberOfChildrenHistogram.txt..." << endl;
|
||||||
|
file.open("SolverComparer_Stats_numberOfChildrenHistogram.txt");
|
||||||
|
treeTraversal::ForestStatistics::Write(file, statistics.numberOfChildrenHistogram);
|
||||||
|
file.close();
|
||||||
|
|
||||||
|
cout << "Writing SolverComparer_Stats_problemSizeOfSecondLargestChildHistogram.txt..." << endl;
|
||||||
|
file.open("SolverComparer_Stats_problemSizeOfSecondLargestChildHistogram.txt");
|
||||||
|
treeTraversal::ForestStatistics::Write(file, statistics.problemSizeOfSecondLargestChildHistogram);
|
||||||
|
file.close();
|
||||||
|
}
|
||||||
|
|
Loading…
Reference in New Issue