38 #include <boost/program_options.hpp> 41 using namespace gtsam;
42 namespace po = boost::program_options;
45 int main(
int argc,
char* argv[]) {
51 po::options_description desc(
52 "Shonan Rotation Averaging CLI reads a *pose* graph, extracts the " 53 "rotation constraints, and runs the Shonan algorithm.");
54 desc.add_options()(
"help",
"Print help message")(
56 po::value<string>(&datasetName)->default_value(
"pose3example-grid"),
57 "Find and read frome example dataset file")(
58 "input_file,i", po::value<string>(&inputFile)->default_value(
""),
59 "Read pose constraints graph from the specified file")(
61 po::value<string>(&outputFile)->default_value(
"shonan.g2o"),
62 "Write solution to the specified file")(
63 "dimension,d", po::value<int>(&d)->default_value(3),
64 "Optimize over 2D or 3D rotations")(
65 "useHuberLoss,h", po::value<bool>(&useHuberLoss)->default_value(
false),
66 "set True to use Huber loss")(
"pMin,p",
67 po::value<int>(&pMin)->default_value(3),
68 "set to use desired rank pMin")(
69 "seed,s", po::value<int>(&seed)->default_value(42),
70 "Random seed for initial estimate");
72 po::store(po::command_line_parser(argc, argv).
options(desc).
run(), vm);
75 if (vm.count(
"help")) {
81 if (inputFile.empty()) {
82 if (datasetName.empty()) {
83 cout <<
"You must either specify a named dataset or an input file\n" 91 static std::mt19937
rng(seed);
94 Values::shared_ptr posesInFile;
96 auto lmParams = LevenbergMarquardtParams::CeresDefaults();
98 cout <<
"Running Shonan averaging for SO(2) on " << inputFile << endl;
100 parameters.setUseHuber(useHuberLoss);
106 std::tie(inputGraph, posesInFile) =
load2D(inputFile);
107 auto priorModel = noiseModel::Unit::Create(3);
108 inputGraph->addPrior(0, posesInFile->at<
Pose2>(0), priorModel);
110 cout <<
"recovering 2D translations" << endl;
111 auto poseGraph = initialize::buildPoseGraph<Pose2>(*inputGraph);
112 poses = initialize::computePoses<Pose2>(
result.first, &poseGraph);
114 cout <<
"Running Shonan averaging for SO(3) on " << inputFile << endl;
116 parameters.setUseHuber(useHuberLoss);
122 std::tie(inputGraph, posesInFile) =
load3D(inputFile);
123 auto priorModel = noiseModel::Unit::Create(6);
124 inputGraph->addPrior(0, posesInFile->at<
Pose3>(0), priorModel);
126 cout <<
"recovering 3D translations" << endl;
127 auto poseGraph = initialize::buildPoseGraph<Pose3>(*inputGraph);
128 poses = initialize::computePoses<Pose3>(
result.first, &poseGraph);
130 cout <<
"Can only run SO(2) or SO(3) averaging\n" << desc << endl;
133 cout <<
"Writing result to " << outputFile << endl;
134 writeG2o(*inputGraph, poses, outputFile);
void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, const std::string &filename)
This function writes a g2o file from NonlinearFactorGraph and a Values structure. ...
Values initializeRandomly(std::mt19937 &rng) const
std::pair< Values, double > run(const Values &initialEstimate, size_t pMin=d, size_t pMax=10) const
common code between lago.* (2D) and InitializePose3.* (3D)
int main(int argc, char *argv[])
idx_t idx_t idx_t idx_t idx_t idx_t idx_t real_t real_t idx_t * options
GraphAndValues load3D(const std::string &filename)
Load TORO 3D Graph.
GraphAndValues load2D(const std::string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
LevenbergMarquardtParams lmParams
static ConjugateGradientParameters parameters
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
std::shared_ptr< This > shared_ptr
utility functions for loading datasets
Shonan Averaging algorithm.