27 #include <Eigen/StdVector> 39 using namespace Eigen;
50 static int uniform(
int from,
int to);
52 static double uniform();
54 static double gaussian(
double sigma);
63 uniform_int_distribution<int> unif(from, to);
64 int sam = unif(gen_int);
70 std::uniform_real_distribution<double> unif(0.0, 1.0);
71 double sam = unif(gen_real);
77 std::normal_distribution<double> gauss(0.0, sigma);
78 double sam = gauss(gen_real);
89 double euc_noise = 0.01;
103 vector<Vector3d> true_points;
104 for (
size_t i=0;i<1000; ++i)
114 for (
size_t i=0; i<2; ++i)
121 Eigen::Isometry3d cam;
123 cam.translation() = t;
129 vc->
setId(vertex_id);
131 cerr << t.transpose() <<
" | " << q.coeffs().transpose() << endl;
144 for (
size_t i=0; i<true_points.size(); ++i)
154 pt0 = vp0->
estimate().inverse() * true_points[i];
155 pt1 = vp1->
estimate().inverse() * true_points[i];
205 Eigen::Isometry3d cam = vc->
estimate();
206 cam.translation() = Vector3d(0,0,0.2);
211 cout <<
"Initial chi2 = " << FIXED(optimizer.
chi2()) << endl;
217 cout << endl <<
"Second vertex should be near 0,0,1" << endl;
218 cout << dynamic_cast<VertexSE3*>(optimizer.
vertices().find(0)->second)
219 ->estimate().translation().transpose() << endl;
220 cout << dynamic_cast<VertexSE3*>(optimizer.
vertices().find(1)->second)
221 ->estimate().translation().transpose() << endl;
Implementation of the Levenberg Algorithm.
static default_random_engine gen_int
int optimize(int iterations, bool online=false)
virtual void setMeasurement(const Measurement &m)
void computeActiveErrors()
linear solver using dense cholesky decomposition
void setVertex(size_t i, Vertex *v)
const VertexIDMap & vertices() const
Traits::LinearSolverType LinearSolverType
virtual void setId(int id)
sets the id of the node in the graph be sure that the graph keeps consistent after changing the id ...
double chi2() const
returns the chi2 of the current configuration
void setVerbose(bool verbose)
void setAlgorithm(OptimizationAlgorithm *algorithm)
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
const EstimateType & estimate() const
return the current estimate of the vertex
Implementation of a solver operating on the blocks of the Hessian.
3D pose Vertex, represented as an Isometry3D
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
static double gaussian(double sigma)
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
static default_random_engine gen_real
BlockSolver< BlockSolverTraits< Eigen::Dynamic, Eigen::Dynamic > > BlockSolverX