23 using namespace gtsam;
25 int main(
int argc,
char *argv[]) {
29 cout <<
"Loading data..." << endl;
32 std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr>
data =
38 cout <<
"Optimizing..." << endl;
44 double lastError = optimizer.
error();
51 cout <<
"Error: " << optimizer.
error() <<
", lambda: " << optimizer.
lambda() << endl;
61 gttic_(marginalInformation);
63 gttoc_(marginalInformation);
70 }
catch(std::exception&
e) {
71 cout << e.what() << endl;
GraphAndValues load2D(const string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
Verbosity verbosity
The printing verbosity during optimization (default SILENT)
NonlinearFactorGraph graph
double absoluteErrorTol
The maximum absolute error decrease to stop iterating (default 1e-5)
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
string findExampleDataFile(const string &name)
double errorTol
The maximum total error to stop iterating (default 0.0)
int main(int argc, char *argv[])
bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold, double errorThreshold, double currentError, double newError, NonlinearOptimizerParams::Verbosity verbosity)
const Values & values() const
return values in current optimizer state
const LevenbergMarquardtParams & params() const
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
double lambda() const
Access the current damping value.
double error() const
return error in current optimizer state
GaussianFactorGraph::shared_ptr iterate() override
A class for computing marginals in a NonlinearFactorGraph.
void tictoc_finishedIteration_()
utility functions for loading datasets
std::uint64_t Key
Integer nonlinear key type.
Marginals marginals(graph, result)
Matrix marginalInformation(Key variable) const