g2o::EdgeSE3* addTransformationEdge(g2o::VertexSE3 *from, g2o::VertexSE3 *to, const dvo::core::AffineTransformd& transform, const dvo::core::Matrix6d& information) { assert(from != 0 && to != 0); g2o::EdgeSE3* edge = new g2o::EdgeSE3(); edge->setId(max_edge_id_++); edge->resize(2); edge->setVertex(0, from); edge->setVertex(1, to); edge->setMeasurement(toIsometry(transform)); edge->setInformation(information); graph_.addEdge(edge); return edge; }
void test() { Isometry3d T = Eigen::Isometry3d::Identity(); T(0,0)=1; T(0,1)=0; T(0,2)=0; T(1,0)=0; T(1,1)=0.707; T(1,2)=-0.707; T(2,0)=0; T(2,1)=0.707; T(2,2)=0.707; T(0,3)=0; T(1,3)=0; T(2,3)=0.5; cout<<T.matrix()<<endl; for (int i = 2; i <=8; i++) { g2o::EdgeSE3* edge = new g2o::EdgeSE3(); g2o::VertexSE3 *v = new g2o::VertexSE3(); v->setId(i); v->setEstimate( Eigen::Isometry3d::Identity() ); m_globalOptimizer.addVertex(v); edge->vertices() [0] = m_globalOptimizer.vertex( i-1 ); edge->vertices() [1] = m_globalOptimizer.vertex( i ); Eigen::Matrix<double, 6, 6> information = Eigen::Matrix< double, 6,6 >::Identity(); information(0,0) = information(1,1) = information(2,2) = 100; information(3,3) = information(4,4) = information(5,5) = 100; edge->setInformation( information ); edge->setMeasurement( T ); m_globalOptimizer.addEdge(edge); } #if 0 T = Eigen::Isometry3d::Identity(); //T(2,3)=1; //cout<<T.matrix()<<endl; g2o::EdgeSE3* edge = new g2o::EdgeSE3(); g2o::VertexSE3 *v = new g2o::VertexSE3(); v->setId(8); v->setEstimate( Eigen::Isometry3d::Identity() ); m_globalOptimizer.addVertex(v); edge->vertices() [0] = m_globalOptimizer.vertex( 1 ); edge->vertices() [1] = m_globalOptimizer.vertex( 8 ); Eigen::Matrix<double, 6, 6> information = Eigen::Matrix< double, 6,6 >::Identity(); information(0,0) = information(1,1) = information(2,2) = 100; information(3,3) = information(4,4) = information(5,5) = 100; edge->setInformation( information ); edge->setMeasurement( T ); m_globalOptimizer.addEdge(edge); #endif m_globalOptimizer.save("pa.g2o"); m_globalOptimizer.initializeOptimization(); //m_globalOptimizer.optimize(50); m_globalOptimizer.save("pa2.g2o"); cout<<"f**k"<<endl; VertexSE3* vertex = dynamic_cast<VertexSE3*>(m_globalOptimizer.vertex(2)); Isometry3d pose = vertex -> estimate(); //cout << "matrix:" << endl; cout << pose.matrix() << endl; }