From 8e7dcaf68ee3ef59c8ca5f8ab0728dcbea6bf696 Mon Sep 17 00:00:00 2001 From: Zhao Zihe <2809075376@qq.com> Date: Sat, 2 Jun 2018 22:21:23 +0800 Subject: [PATCH 1/2] Update new version of G2O MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit 更新了新版G2O接口,BlockSolver的构造器是unique_ptr的,unique_ptr不支持拷贝构造,所以传参必须通过move。 --- ch7/pose_estimation_3d2d.cpp | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/ch7/pose_estimation_3d2d.cpp b/ch7/pose_estimation_3d2d.cpp index 2daf8bb19..ad4ffb9a9 100644 --- a/ch7/pose_estimation_3d2d.cpp +++ b/ch7/pose_estimation_3d2d.cpp @@ -146,27 +146,32 @@ void bundleAdjustment ( Mat& R, Mat& t ) { // 初始化g2o + // 初始化部分需要改成unique_ptr的, 2018年06月01日17:54:25 typedef g2o::BlockSolver< g2o::BlockSolverTraits<6,3> > Block; // pose 维度为 6, landmark 维度为 3 - Block::LinearSolverType* linearSolver = new g2o::LinearSolverCSparse(); // 线性方程求解器 - Block* solver_ptr = new Block ( linearSolver ); // 矩阵块求解器 - g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg ( solver_ptr ); + std::unique_ptr linearSolver (new g2o::LinearSolverCSparse()); // 线性方程求解器 + std::unique_ptr solver_ptr( new Block(std::move(linearSolver))); // 矩阵块求解器 + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg ( std::move(solver_ptr) ); g2o::SparseOptimizer optimizer; optimizer.setAlgorithm ( solver ); - // vertex + // vertex(se(3), R, t g2o::VertexSE3Expmap* pose = new g2o::VertexSE3Expmap(); // camera pose Eigen::Matrix3d R_mat; R_mat << - R.at ( 0,0 ), R.at ( 0,1 ), R.at ( 0,2 ), + R.at ( 0,0 ), R.at ( 0,1 ), R.at ( 0,2 ), R.at ( 1,0 ), R.at ( 1,1 ), R.at ( 1,2 ), R.at ( 2,0 ), R.at ( 2,1 ), R.at ( 2,2 ); + pose->setId ( 0 ); - pose->setEstimate ( g2o::SE3Quat ( + pose->setEstimate ( g2o::SE3Quat ( //si yuan shu {R}, t R_mat, Eigen::Vector3d ( t.at ( 0,0 ), t.at ( 1,0 ), t.at ( 2,0 ) ) - ) ); + ) + ); + optimizer.addVertex ( pose ); + // vertex (Pos in world axes) int index = 1; for ( const Point3f p:points_3d ) // landmarks { From a442111aac2b905bf6f8e2c4be38f7bc5704b3bd Mon Sep 17 00:00:00 2001 From: Zhao Zihe <2809075376@qq.com> Date: Sat, 2 Jun 2018 22:24:25 +0800 Subject: [PATCH 2/2] Update new verison of G2O MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit 更新了新版G2O接口,BlockSolver的构造器是unique_ptr的,unique_ptr不支持拷贝构造,所以传参必须通过move。 --- ch6/g2o_curve_fitting/main.cpp | 20 ++++++++++++++------ 1 file changed, 14 insertions(+), 6 deletions(-) diff --git a/ch6/g2o_curve_fitting/main.cpp b/ch6/g2o_curve_fitting/main.cpp index 946a912db..300125adf 100644 --- a/ch6/g2o_curve_fitting/main.cpp +++ b/ch6/g2o_curve_fitting/main.cpp @@ -73,12 +73,20 @@ int main( int argc, char** argv ) // 构建图优化,先设定g2o typedef g2o::BlockSolver< g2o::BlockSolverTraits<3,1> > Block; // 每个误差项优化变量维度为3,误差值维度为1 - Block::LinearSolverType* linearSolver = new g2o::LinearSolverDense(); // 线性方程求解器 - Block* solver_ptr = new Block( linearSolver ); // 矩阵块求解器 + + //-----修改以下注释到下行代码-----------// + // Block::LinearSolverType* linearSolver = new g2o::LinearSolverDense(); // 线性方程求解器 + std::unique_ptr linearSolver ( new g2o::LinearSolverDense()); + + //-----修改以下注释到下行代码-----------// + //Block* solver_ptr = new Block( linearSolver ); // 矩阵块求解器 + std::unique_ptr solver_ptr ( new Block ( std::move(linearSolver))); + // 梯度下降方法,从GN, LM, DogLeg 中选 - g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg( solver_ptr ); - // g2o::OptimizationAlgorithmGaussNewton* solver = new g2o::OptimizationAlgorithmGaussNewton( solver_ptr ); - // g2o::OptimizationAlgorithmDogleg* solver = new g2o::OptimizationAlgorithmDogleg( solver_ptr ); + //-----修改以下注释到下行代码-----------// + // g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg( solver_ptr ); + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg ( std::move(solver_ptr)); + g2o::SparseOptimizer optimizer; // 图模型 optimizer.setAlgorithm( solver ); // 设置求解器 optimizer.setVerbose( true ); // 打开调试输出 @@ -114,4 +122,4 @@ int main( int argc, char** argv ) cout<<"estimated model: "<