Add prior and sanitize printing

release/4.3a0
Frank Dellaert 2025-01-24 15:02:18 -05:00
parent be5d30c57a
commit c60d257e80
1 changed files with 10 additions and 12 deletions

View File

@ -29,18 +29,16 @@ int main(int argc, char *argv[]) {
cout << "Loading data..." << endl; cout << "Loading data..." << endl;
string datasetFile = findExampleDataFile("w10000"); string datasetFile = findExampleDataFile("w10000");
std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr> data = auto [graph, initial] = load2D(datasetFile);
load2D(datasetFile); graph->addPrior(0, initial->at<Pose2>(0), noiseModel::Unit::Create(3));
NonlinearFactorGraph graph = *data.first;
Values initial = *data.second;
cout << "Optimizing..." << endl; cout << "Optimizing..." << endl;
gttic_(Create_optimizer); gttic_(Create_optimizer);
LevenbergMarquardtOptimizer optimizer(graph, initial); LevenbergMarquardtOptimizer optimizer(*graph, *initial);
gttoc_(Create_optimizer); gttoc_(Create_optimizer);
tictoc_print_(); tictoc_print_();
tictoc_reset_();
double lastError = optimizer.error(); double lastError = optimizer.error();
do { do {
gttic_(Iterate_optimizer); gttic_(Iterate_optimizer);
@ -53,19 +51,19 @@ int main(int argc, char *argv[]) {
} while(!checkConvergence(optimizer.params().relativeErrorTol, } while(!checkConvergence(optimizer.params().relativeErrorTol,
optimizer.params().absoluteErrorTol, optimizer.params().errorTol, optimizer.params().absoluteErrorTol, optimizer.params().errorTol,
lastError, optimizer.error(), optimizer.params().verbosity)); lastError, optimizer.error(), optimizer.params().verbosity));
tictoc_reset_();
// Compute marginals // Compute marginals
Marginals marginals(graph, optimizer.values()); gttic_(ConstructMarginals);
int i=0; Marginals marginals(*graph, optimizer.values());
for(Key key: initial.keys()) { gttoc_(ConstructMarginals);
for(Key key: initial->keys()) {
gttic_(marginalInformation); gttic_(marginalInformation);
Matrix info = marginals.marginalInformation(key); Matrix info = marginals.marginalInformation(key);
gttoc_(marginalInformation); gttoc_(marginalInformation);
tictoc_finishedIteration_(); tictoc_finishedIteration_();
if(i % 1000 == 0)
tictoc_print_();
++i;
} }
tictoc_print_();
} catch(std::exception& e) { } catch(std::exception& e) {
cout << e.what() << endl; cout << e.what() << endl;