formatting
parent
3e6efe3a51
commit
799788672f
|
@ -25,7 +25,8 @@
|
||||||
* Read 3D dataset sphere25000.txt and output to shonan.g2o (default)
|
* Read 3D dataset sphere25000.txt and output to shonan.g2o (default)
|
||||||
* ./ShonanAveragingCLI -i spere2500.txt
|
* ./ShonanAveragingCLI -i spere2500.txt
|
||||||
*
|
*
|
||||||
* If you prefer using a robust Huber loss, you can add the option "-h true", for instance
|
* If you prefer using a robust Huber loss, you can add the option "-h true",
|
||||||
|
* for instance
|
||||||
* ./ShonanAveragingCLI -i spere2500.txt -u true
|
* ./ShonanAveragingCLI -i spere2500.txt -u true
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
@ -62,9 +63,9 @@ int main(int argc, char* argv[]) {
|
||||||
"dimension,d", po::value<int>(&d)->default_value(3),
|
"dimension,d", po::value<int>(&d)->default_value(3),
|
||||||
"Optimize over 2D or 3D rotations")(
|
"Optimize over 2D or 3D rotations")(
|
||||||
"useHuberLoss,h", po::value<bool>(&useHuberLoss)->default_value(false),
|
"useHuberLoss,h", po::value<bool>(&useHuberLoss)->default_value(false),
|
||||||
"set True to use Huber loss")(
|
"set True to use Huber loss")("pMin,p",
|
||||||
"pMin,p", po::value<int>(&pMin)->default_value(3),
|
po::value<int>(&pMin)->default_value(3),
|
||||||
"set to use desired rank pMin")(
|
"set to use desired rank pMin")(
|
||||||
"seed,s", po::value<int>(&seed)->default_value(42),
|
"seed,s", po::value<int>(&seed)->default_value(42),
|
||||||
"Random seed for initial estimate");
|
"Random seed for initial estimate");
|
||||||
po::variables_map vm;
|
po::variables_map vm;
|
||||||
|
@ -97,9 +98,9 @@ int main(int argc, char* argv[]) {
|
||||||
cout << "Running Shonan averaging for SO(2) on " << inputFile << endl;
|
cout << "Running Shonan averaging for SO(2) on " << inputFile << endl;
|
||||||
ShonanAveraging2::Parameters parameters(lmParams);
|
ShonanAveraging2::Parameters parameters(lmParams);
|
||||||
parameters.setUseHuber(useHuberLoss);
|
parameters.setUseHuber(useHuberLoss);
|
||||||
ShonanAveraging2 shonan(inputFile,parameters);
|
ShonanAveraging2 shonan(inputFile, parameters);
|
||||||
auto initial = shonan.initializeRandomly(rng);
|
auto initial = shonan.initializeRandomly(rng);
|
||||||
auto result = shonan.run(initial,pMin);
|
auto result = shonan.run(initial, pMin);
|
||||||
|
|
||||||
// Parse file again to set up translation problem, adding a prior
|
// Parse file again to set up translation problem, adding a prior
|
||||||
boost::tie(inputGraph, posesInFile) = load2D(inputFile);
|
boost::tie(inputGraph, posesInFile) = load2D(inputFile);
|
||||||
|
@ -113,9 +114,9 @@ int main(int argc, char* argv[]) {
|
||||||
cout << "Running Shonan averaging for SO(3) on " << inputFile << endl;
|
cout << "Running Shonan averaging for SO(3) on " << inputFile << endl;
|
||||||
ShonanAveraging3::Parameters parameters(lmParams);
|
ShonanAveraging3::Parameters parameters(lmParams);
|
||||||
parameters.setUseHuber(useHuberLoss);
|
parameters.setUseHuber(useHuberLoss);
|
||||||
ShonanAveraging3 shonan(inputFile,parameters);
|
ShonanAveraging3 shonan(inputFile, parameters);
|
||||||
auto initial = shonan.initializeRandomly(rng);
|
auto initial = shonan.initializeRandomly(rng);
|
||||||
auto result = shonan.run(initial,pMin);
|
auto result = shonan.run(initial, pMin);
|
||||||
|
|
||||||
// Parse file again to set up translation problem, adding a prior
|
// Parse file again to set up translation problem, adding a prior
|
||||||
boost::tie(inputGraph, posesInFile) = load3D(inputFile);
|
boost::tie(inputGraph, posesInFile) = load3D(inputFile);
|
||||||
|
|
Loading…
Reference in New Issue