g2o
Loading...
Searching...
No Matches
Classes | Functions
curve_fit.cpp File Reference
#include <Eigen/Core>
#include <iostream>
#include "g2o/core/auto_differentiation.h"
#include "g2o/core/base_unary_edge.h"
#include "g2o/core/base_vertex.h"
#include "g2o/core/optimization_algorithm_factory.h"
#include "g2o/core/sparse_optimizer.h"
#include "g2o/stuff/command_args.h"
#include "g2o/stuff/sampler.h"
Include dependency graph for curve_fit.cpp:

Go to the source code of this file.

Classes

class  VertexParams
 the params, a, b, and lambda for a * exp(-lambda * t) + b More...
 
class  EdgePointOnCurve
 measurement for a point on the curve More...
 

Functions

 G2O_USE_OPTIMIZATION_LIBRARY (dense)
 
int main (int argc, char **argv)
 

Function Documentation

◆ G2O_USE_OPTIMIZATION_LIBRARY()

G2O_USE_OPTIMIZATION_LIBRARY ( dense  )

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 96 of file curve_fit.cpp.

96 {
97 int numPoints;
98 int maxIterations;
99 bool verbose;
100 string dumpFilename;
102 arg.param("dump", dumpFilename, "", "dump the points into a file");
103 arg.param("numPoints", numPoints, 50,
104 "number of points sampled from the curve");
105 arg.param("i", maxIterations, 10, "perform n iterations");
106 arg.param("v", verbose, false, "verbose output of the optimization process");
107
108 arg.parseArgs(argc, argv);
109
110 // generate random data
112 double a = 2.;
113 double b = 0.4;
114 double lambda = 0.2;
115 Eigen::Vector2d* points = new Eigen::Vector2d[numPoints];
116 for (int i = 0; i < numPoints; ++i) {
117 double x = g2o::Sampler::uniformRand(0, 10);
118 double y = a * exp(-lambda * x) + b;
119 // add Gaussian noise
120 y += g2o::Sampler::gaussRand(0, 0.02);
121 points[i].x() = x;
122 points[i].y() = y;
123 }
124
125 if (dumpFilename.size() > 0) {
126 ofstream fout(dumpFilename.c_str());
127 for (int i = 0; i < numPoints; ++i) fout << points[i].transpose() << endl;
128 }
129
130 // setup the solver
131 g2o::SparseOptimizer optimizer;
132 optimizer.setVerbose(false);
133
134 // allocate the solver
136 optimizer.setAlgorithm(
137 g2o::OptimizationAlgorithmFactory::instance()->construct("lm_dense",
138 solverProperty));
139
140 // build the optimization problem given the points
141 // 1. add the parameter vertex
142 VertexParams* params = new VertexParams();
143 params->setId(0);
144 params->setEstimate(
145 Eigen::Vector3d(1, 1, 1)); // some initial value for the params
146 optimizer.addVertex(params);
147 // 2. add the points we measured to be on the curve
148 for (int i = 0; i < numPoints; ++i) {
150 e->setInformation(Eigen::Matrix<double, 1, 1>::Identity());
151 e->setVertex(0, params);
152 e->setMeasurement(points[i]);
153 optimizer.addEdge(e);
154 }
155
156 // perform the optimization
157 optimizer.initializeOptimization();
158 optimizer.setVerbose(verbose);
159 optimizer.optimize(maxIterations);
160
161 if (verbose) cout << endl;
162
163 // print out the result
164 cout << "Target curve" << endl;
165 cout << "a * exp(-lambda * x) + b" << endl;
166 cout << "Iterative least squares solution" << endl;
167 cout << "a = " << params->estimate()(0) << endl;
168 cout << "b = " << params->estimate()(1) << endl;
169 cout << "lambda = " << params->estimate()(2) << endl;
170 cout << endl;
171
172 // clean up
173 delete[] points;
174
175 return 0;
176}
measurement for a point on the curve
Definition curve_fit.cpp:70
the params, a, b, and lambda for a * exp(-lambda * t) + b
Definition curve_fit.cpp:45
virtual void setMeasurement(const Measurement &m)
Definition base_edge.h:122
void setInformation(const InformationType &information)
Definition base_edge.h:111
const EstimateType & estimate() const
return the current estimate of the vertex
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Command line parsing of argc and argv.
bool parseArgs(int argc, char **argv, bool exitOnError=true)
void param(const std::string &name, bool &p, bool defValue, const std::string &desc)
void setVertex(size_t i, Vertex *v)
static OptimizationAlgorithmFactory * instance()
return the instance
static void seedRand()
Definition sampler.h:109
static double gaussRand(double mean, double sigma)
Definition sampler.h:89
static double uniformRand(double lowerBndr, double upperBndr)
Definition sampler.h:102
int optimize(int iterations, bool online=false)
void setVerbose(bool verbose)
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
void setAlgorithm(OptimizationAlgorithm *algorithm)
Jet< T, N > exp(const Jet< T, N > &f)
Definition jet.h:437
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)

References g2o::OptimizableGraph::addEdge(), g2o::OptimizableGraph::addVertex(), g2o::BaseVertex< D, T >::estimate(), g2o::Sampler::gaussRand(), g2o::SparseOptimizer::initializeOptimization(), g2o::OptimizationAlgorithmFactory::instance(), g2o::SparseOptimizer::optimize(), g2o::CommandArgs::param(), g2o::CommandArgs::parseArgs(), g2o::Sampler::seedRand(), g2o::SparseOptimizer::setAlgorithm(), g2o::BaseVertex< D, T >::setEstimate(), g2o::OptimizableGraph::Vertex::setId(), g2o::BaseEdge< D, E >::setInformation(), g2o::BaseEdge< D, E >::setMeasurement(), g2o::SparseOptimizer::setVerbose(), g2o::HyperGraph::Edge::setVertex(), and g2o::Sampler::uniformRand().