27 #include <Eigen/StdVector> 39 using namespace Eigen;
47 static default_random_engine gen_real;
48 static default_random_engine gen_int;
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);
87 int main(
int argc,
char **argv)
93 num_points = atoi(argv[1]);
95 double euc_noise = 0.1;
96 double pix_noise = 1.0;
116 vector<Vector3d> true_points;
117 for (
size_t i=0;i<1000; ++i)
126 Vector2d focal_length(500,500);
127 Vector2d principal_point(320,240);
128 double baseline = 0.075;
132 principal_point[0],principal_point[1],
138 for (
size_t i=0; i<2; ++i)
145 Eigen::Isometry3d cam;
147 cam.translation() = t;
152 vc->
setId(vertex_id);
154 cerr << t.transpose() <<
" | " << q.coeffs().transpose() << endl;
170 for (
size_t i=0; i<true_points.size(); ++i)
180 pt0 = vp0->
estimate().inverse() * true_points[i];
181 pt1 = vp1->
estimate().inverse() * true_points[i];
233 for (
int i=0;i<num_points; ++i)
242 for (
size_t i=0; i<true_points.size(); ++i)
248 v_p->
setId(vertex_id++);
257 for (
size_t j=0; j<2; ++j)
261 (optimizer.
vertices().find(j)->second)
262 ->mapPoint(z,true_points.at(i));
264 if (z[0]>=0 && z[1]>=0 && z[0]<640 && z[1]<480)
278 (optimizer.
vertices().find(j)->second);
298 Eigen::Isometry3d cam = vc->
estimate();
299 cam.translation() = Vector3d(-0.1,0.1,0.2);
303 cout <<
"Initial chi2 = " << FIXED(optimizer.
chi2()) << endl;
309 cout << endl <<
"Second vertex should be near 0,0,1" << endl;
310 cout << dynamic_cast<VertexSE3*>(optimizer.
vertices().find(0)->second)
311 ->estimate().translation().transpose() << endl;
312 cout << dynamic_cast<VertexSE3*>(optimizer.
vertices().find(1)->second)
313 ->estimate().translation().transpose() << endl;
int main(int argc, char **argv)
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()
Traits::PoseMatrixType PoseMatrixType
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
const VertexContainer & vertices() const
void setVerbose(bool verbose)
linear solver which uses CSparse
void setAlgorithm(OptimizationAlgorithm *algorithm)
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
A general case Vertex for optimization.
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
void setMarginalized(bool marginalized)
true => this node should be marginalized out during the optimization
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)
static void setKcam(double fx, double fy, double cx, double cy, double tx)
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
Point vertex, XYZ, is in types_sba.
Stereo camera vertex, derived from SE3 class. Note that we use the actual pose of the vertex as its p...
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