29 using namespace gtsam;
31 int main (
int argc,
char** argv) {
39 boost::tie(graph, initial) =
load2D(graph_file, model);
40 initial->print(
"Initial estimate:\n");
45 graph ->
addPrior(0, priorMean, priorNoise);
49 result.
print(
"\nFinal result:\n");
virtual const Values & optimize()
noiseModel::Diagonal::shared_ptr model
GraphAndValues load2D(const string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
NonlinearFactorGraph graph
string findExampleDataFile(const string &name)
int main(int argc, char **argv)
boost::shared_ptr< This > shared_ptr
Pose2 priorMean(0.0, 0.0, 0.0)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
noiseModel::Diagonal::shared_ptr SharedDiagonal
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
graph addPrior(1, priorMean, priorNoise)
Matrix marginalCovariance(Key variable) const
A class for computing marginals in a NonlinearFactorGraph.
noiseModel::Diagonal::shared_ptr priorNoise
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
utility functions for loading datasets
Marginals marginals(graph, result)