视觉SLAM的ICP问题——SVD及G2O求解

16 篇文章 1 订阅
11 篇文章 1 订阅

ICP问题

  • 迭代最近点法(ICP)可以用来求解两组三维图像(或三维点云)间的位姿变换关系。可以通过奇异值分解或非线性优化方式求解。
    关于ICP求解的推导公式均在课本第七讲。
  • 下面分别介绍SVD求解方法、自定义顶点的G2O求解方法、采用内置顶点的G2O求解方法。

SVD求解方法

void pose_estimation_3d3d (
    const vector<Point3f>& pts1,
    const vector<Point3f>& pts2,
    Mat& R, Mat& t
)
{
    Point3f p1, p2;     // center of mass
    int N = pts1.size();
    //以下是求解两组点的质心p1、p2
    for ( int i=0; i<N; i++ )
    {
        p1 += pts1[i];
        p2 += pts2[i];
    }
    p1 = Point3f( Vec3f(p1) /  N);
    p2 = Point3f( Vec3f(p2) / N);
	//以下是求解每个点的去质心坐标
    vector<Point3f>     q1 ( N ), q2 ( N ); // remove the center
    for ( int i=0; i<N; i++ )
    {
        q1[i] = pts1[i] - p1;
        q2[i] = pts2[i] - p2;
    }

    // compute q1*q2^T,也就是W矩阵
    Eigen::Matrix3d W = Eigen::Matrix3d::Zero();
    for ( int i=0; i<N; i++ )
    {
        W += Eigen::Vector3d ( q1[i].x, q1[i].y, q1[i].z ) * Eigen::Vector3d ( q2[i].x, q2[i].y, q2[i].z ).transpose();
    }
    cout<<"W="<<W<<endl;

    // SVD on W,求解SVD问题
    Eigen::JacobiSVD<Eigen::Matrix3d> svd ( W, Eigen::ComputeFullU|Eigen::ComputeFullV );
    Eigen::Matrix3d U = svd.matrixU();
    Eigen::Matrix3d V = svd.matrixV();
    
    if (U.determinant() * V.determinant() < 0)
	{
        for (int x = 0; x < 3; ++x)
        {
            U(x, 2) *= -1;
        }
	}
    
    cout<<"U="<<U<<endl;
    cout<<"V="<<V<<endl;
	//R
    Eigen::Matrix3d R_ = U* ( V.transpose() );
    //t
    Eigen::Vector3d t_ = Eigen::Vector3d ( p1.x, p1.y, p1.z ) - R_ * Eigen::Vector3d ( p2.x, p2.y, p2.z );

    // convert to cv::Mat
    R = ( Mat_<double> ( 3,3 ) <<
          R_ ( 0,0 ), R_ ( 0,1 ), R_ ( 0,2 ),
          R_ ( 1,0 ), R_ ( 1,1 ), R_ ( 1,2 ),
          R_ ( 2,0 ), R_ ( 2,1 ), R_ ( 2,2 )
        );
    t = ( Mat_<double> ( 3,1 ) << t_ ( 0,0 ), t_ ( 1,0 ), t_ ( 2,0 ) );
}

输出结果:

W=  10.871 -1.01948  2.54771
-2.16033  3.85307 -5.77742
 3.94738 -5.79979  9.62203
U=  0.558087  -0.829399 -0.0252034
 -0.428009  -0.313755   0.847565
  0.710878   0.462228   0.530093
V=  0.617887  -0.784771 -0.0484806
 -0.399894  -0.366747   0.839989
  0.676979   0.499631   0.540434
ICP via SVD results: 
R = [0.9969452351705237, 0.05983347594296956, -0.05020112774999552;
 -0.05932607556034199, 0.9981719680327529, 0.01153858709846614;
 0.05079975225724803, -0.008525103530305804, 0.998672472725868]
t = [0.1441598281917406;
 -0.06667849447794763;
 -0.03009747343724323]
R_inv = [0.9969452351705237, -0.05932607556034199, 0.05079975225724803;
 0.05983347594296956, 0.9981719680327529, -0.008525103530305804;
 -0.05020112774999552, 0.01153858709846614, 0.998672472725868]
t_inv = [-0.1461462830262246;
 0.05767443636940777;
 0.03806387978797219]

自定义顶点的G2O求解

注意在边的定义中给出了两种雅可比矩阵函数的定义方式,其实内容是一样的,只不过前一种用了Sophus的反对称矩阵函数与Eigen的单位阵函数。

//位姿类型为SE3
class VertexPose : public g2o::BaseVertex<6, Sophus::SE3> {
public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW;

  virtual void setToOriginImpl() override {
    _estimate = Sophus::SE3();
  }
//左乘扰动更新
  /// left multiplication on SE3
  virtual void oplusImpl(const double *update) override {
    Eigen::Matrix<double, 6, 1> update_eigen;
    update_eigen << update[0], update[1], update[2], update[3], update[4], update[5];
    _estimate = Sophus::SE3::exp(update_eigen) * _estimate;
  }

  virtual bool read(istream &in) override {}

  virtual bool write(ostream &out) const override {}
};

// g2o edge
class EdgeProjectXYZRGBDPoseOnly : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, VertexPose>
{
public:
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
    EdgeProjectXYZRGBDPoseOnly( const Eigen::Vector3d& point ) : _point(point) {}

    virtual void computeError()
    {
        const VertexPose* pose = static_cast<const VertexPose*> ( _vertices[0] );
        // measurement is p, point is p'
        _error = _measurement - pose->estimate()* _point ;
    }

    virtual void linearizeOplus()
    {
        VertexPose* pose = static_cast<VertexPose *>(_vertices[0]);
        Sophus::SE3 T(pose->estimate());
        Eigen::Vector3d xyz_trans = T*_point;
        //第一种雅可比矩阵定义方式
        /*
        _jacobianOplusXi.block<3,3>(0,3) = Sophus::SO3::hat(xyz_trans);
        _jacobianOplusXi.block<3,3>(0,0) = -Eigen::Matrix3d::Identity();
        */
        
        //第二种雅可比矩阵定义方式
        double x = xyz_trans[0];
        double y = xyz_trans[1];
        double z = xyz_trans[2];

        _jacobianOplusXi(0,0) = -1;
        _jacobianOplusXi(0,1) = 0;
        _jacobianOplusXi(0,2) = 0;
        _jacobianOplusXi(0,3) = 0;
        _jacobianOplusXi(0,4) = -z;
        _jacobianOplusXi(0,5) = y;

        _jacobianOplusXi(1,0) = 0;
        _jacobianOplusXi(1,1) = -1;
        _jacobianOplusXi(1,2) = 0;
        _jacobianOplusXi(1,3) = z;
        _jacobianOplusXi(1,4) = 0;
        _jacobianOplusXi(1,5) = -x;

        _jacobianOplusXi(2,0) = 0;
        _jacobianOplusXi(2,1) = 0;
        _jacobianOplusXi(2,2) = -1;
        _jacobianOplusXi(2,3) = -y;
        _jacobianOplusXi(2,4) = x;
        _jacobianOplusXi(2,5) = 0;
        
    }

    bool read ( istream& in ) {}
    bool write ( ostream& out ) const {}
protected:
    Eigen::Vector3d _point;
};
void bundleAdjustment (
    const vector< Point3f >& pts1,
    const vector< Point3f >& pts2,
    Mat& R, Mat& t )
{
    // 初始化g2o
    typedef g2o::BlockSolver< g2o::BlockSolverTraits<6,3> > Block;  // pose维度为 6, landmark 维度为 3
    Block::LinearSolverType* linearSolver = new g2o::LinearSolverEigen<Block::PoseMatrixType>(); // 线性方程求解器
    Block* solver_ptr = new Block( linearSolver );      // 矩阵块求解器
    g2o::OptimizationAlgorithmGaussNewton* solver = new g2o::OptimizationAlgorithmGaussNewton( solver_ptr );
    g2o::SparseOptimizer optimizer;
    optimizer.setAlgorithm( solver );

    // vertex
    VertexPose *pose = new VertexPose(); // camera pose
    pose->setId(0);
    pose->setEstimate(Sophus::SE3());
    optimizer.addVertex(pose);
    

      // edges
    for (size_t i = 0; i < pts1.size(); i++) {
    EdgeProjectXYZRGBDPoseOnly *edge = new EdgeProjectXYZRGBDPoseOnly(
      Eigen::Vector3d(pts2[i].x, pts2[i].y, pts2[i].z));
    edge->setVertex(0, pose);
    edge->setMeasurement(Eigen::Vector3d(
      pts1[i].x, pts1[i].y, pts1[i].z));
    edge->setInformation(Eigen::Matrix3d::Identity());
    optimizer.addEdge(edge);
  }

    chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
    optimizer.setVerbose( true );
    optimizer.initializeOptimization();
    optimizer.optimize(5);
    chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
    chrono::duration<double> time_used = chrono::duration_cast<chrono::duration<double>>(t2-t1);
    cout<<"optimization costs time: "<<time_used.count()<<" seconds."<<endl;

    cout<<endl<<"after optimization:"<<endl;
    cout<<"T="<<endl<<pose->estimate().matrix()<<endl;

}

输出结果:

calling bundle adjustment
iteration= 0	 chi2= 1.816115	 time= 0.000261961	 cumTime= 0.000261961	 edges= 72	 schur= 0
iteration= 1	 chi2= 1.815514	 time= 1.2887e-05	 cumTime= 0.000274848	 edges= 72	 schur= 0
iteration= 2	 chi2= 1.815514	 time= 6.8924e-05	 cumTime= 0.000343772	 edges= 72	 schur= 0
iteration= 3	 chi2= 1.815514	 time= 4.025e-05	 cumTime= 0.000384022	 edges= 72	 schur= 0
iteration= 4	 chi2= 1.815514	 time= 1.1597e-05	 cumTime= 0.000395619	 edges= 72	 schur= 0
optimization costs time: 0.000640925 seconds.

after optimization:
T=
  0.996945  0.0598335 -0.0502011    0.14416
-0.0593261   0.998172  0.0115386 -0.0666785
 0.0507998 -0.0085251   0.998672 -0.0300979
         0          0          0          1

采用G2O内置顶点的G2O求解

顶点采用g2o::VertexSE3Expmap类型,边由自己定义,细心点可以发现雅可比的计算函数与上文中的前三列与后三列对调了,这是由于位姿的类型变味了SE3quat引起的。

// g2o edge
class EdgeProjectXYZRGBDPoseOnly : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexSE3Expmap>
{
public:
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
    EdgeProjectXYZRGBDPoseOnly( const Eigen::Vector3d& point ) : _point(point) {}

    virtual void computeError()
    {
        const g2o::VertexSE3Expmap* pose = static_cast<const g2o::VertexSE3Expmap*> ( _vertices[0] );
        // measurement is p, point is p'
        _error = _measurement - pose->estimate().map( _point );
    }

    virtual void linearizeOplus()
    {
        g2o::VertexSE3Expmap* pose = static_cast<g2o::VertexSE3Expmap *>(_vertices[0]);
        g2o::SE3Quat T(pose->estimate());
        Eigen::Vector3d xyz_trans = T.map(_point);
        
        _jacobianOplusXi.block<3,3>(0,0) = Sophus::SO3::hat(xyz_trans);
        _jacobianOplusXi.block<3,3>(0,3) = -Eigen::Matrix3d::Identity();
        
        /*
        double x = xyz_trans[0];
        double y = xyz_trans[1];
        double z = xyz_trans[2];

        _jacobianOplusXi(0,0) = 0;
        _jacobianOplusXi(0,1) = -z;
        _jacobianOplusXi(0,2) = y;
        _jacobianOplusXi(0,3) = -1;
        _jacobianOplusXi(0,4) = 0;
        _jacobianOplusXi(0,5) = 0;

        _jacobianOplusXi(1,0) = z;
        _jacobianOplusXi(1,1) = 0;
        _jacobianOplusXi(1,2) = -x;
        _jacobianOplusXi(1,3) = 0;
        _jacobianOplusXi(1,4) = -1;
        _jacobianOplusXi(1,5) = 0;

        _jacobianOplusXi(2,0) = -y;
        _jacobianOplusXi(2,1) = x;
        _jacobianOplusXi(2,2) = 0;
        _jacobianOplusXi(2,3) = 0;
        _jacobianOplusXi(2,4) = 0;
        _jacobianOplusXi(2,5) = -1;
        */
    }

    bool read ( istream& in ) {}
    bool write ( ostream& out ) const {}
protected:
    Eigen::Vector3d _point;
};
void bundleAdjustment (
    const vector< Point3f >& pts1,
    const vector< Point3f >& pts2,
    Mat& R, Mat& t )
{
    // 初始化g2o
    typedef g2o::BlockSolver< g2o::BlockSolverTraits<6,3> > Block;  // pose维度为 6, landmark 维度为 3
    Block::LinearSolverType* linearSolver = new g2o::LinearSolverEigen<Block::PoseMatrixType>(); // 线性方程求解器
    Block* solver_ptr = new Block( linearSolver );      // 矩阵块求解器
    g2o::OptimizationAlgorithmGaussNewton* solver = new g2o::OptimizationAlgorithmGaussNewton( solver_ptr );
    g2o::SparseOptimizer optimizer;
    optimizer.setAlgorithm( solver );

    // vertex
    g2o::VertexSE3Expmap* pose = new g2o::VertexSE3Expmap(); // camera pose
    pose->setId(0);
    pose->setEstimate( g2o::SE3Quat(
        Eigen::Matrix3d::Identity(),
        Eigen::Vector3d( 0,0,0 )
    ) );
    optimizer.addVertex( pose );

    // edges
    int index = 1;
    vector<EdgeProjectXYZRGBDPoseOnly*> edges;
    for ( size_t i=0; i<pts1.size(); i++ )
    {
        EdgeProjectXYZRGBDPoseOnly* edge = new EdgeProjectXYZRGBDPoseOnly(
            Eigen::Vector3d(pts2[i].x, pts2[i].y, pts2[i].z) );
        edge->setId( index );
        edge->setVertex( 0, dynamic_cast<g2o::VertexSE3Expmap*> (pose) );
        edge->setMeasurement( Eigen::Vector3d(
            pts1[i].x, pts1[i].y, pts1[i].z) );
        edge->setInformation( Eigen::Matrix3d::Identity()*1e4 );
        optimizer.addEdge(edge);
        index++;
        edges.push_back(edge);
    }

    chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
    optimizer.setVerbose( true );
    optimizer.initializeOptimization();
    optimizer.optimize(5);
    chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
    chrono::duration<double> time_used = chrono::duration_cast<chrono::duration<double>>(t2-t1);
    cout<<"optimization costs time: "<<time_used.count()<<" seconds."<<endl;

    cout<<endl<<"after optimization:"<<endl;
    cout<<"T="<<endl<<Eigen::Isometry3d( pose->estimate() ).matrix()<<endl;

}

输出结果为:

calling bundle adjustment
iteration= 0	 chi2= 18161.146626	 time= 0.000122875	 cumTime= 0.000122875	 edges= 72	 schur= 0
iteration= 1	 chi2= 18155.141919	 time= 1.2375e-05	 cumTime= 0.00013525	 edges= 72	 schur= 0
iteration= 2	 chi2= 18155.140765	 time= 1.1205e-05	 cumTime= 0.000146455	 edges= 72	 schur= 0
iteration= 3	 chi2= 18155.140764	 time= 1.4397e-05	 cumTime= 0.000160852	 edges= 72	 schur= 0
iteration= 4	 chi2= 18155.140764	 time= 1.9675e-05	 cumTime= 0.000180527	 edges= 72	 schur= 0
optimization costs time: 0.00590094 seconds.

after optimization:
T=
  0.996945  0.0598335 -0.0502011    0.14416
-0.0593261   0.998172  0.0115386 -0.0666785
 0.0507998 -0.0085251   0.998672 -0.0300979
         0          0          0          1

CMakeLists.txt

这是和上一篇文章的cmake文件写到一起了:

cmake_minimum_required(VERSION 2.8)
project(vo1)

set(CMAKE_BUILD_TYPE "Release")
add_definitions("-DENABLE_SSE")
set(CMAKE_CXX_FLAGS "-std=c++11 -O2 ${SSE_FLAGS} -g -march=native")
list(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)

find_package(OpenCV  REQUIRED)
find_package(Sophus REQUIRED)
find_package( G2O REQUIRED )
find_package( CSparse REQUIRED )


include_directories(
        ${OpenCV_INCLUDE_DIRS}
        ${Sophus_INCLUDE_DIRS}
        ${G2O_INCLUDE_DIRS}
        ${CSPARSE_INCLUDE_DIR}
        "/usr/include/eigen3/"
)


add_executable(pose_estimation_3d2d 3d2d.cpp)
target_link_libraries(pose_estimation_3d2d
        ${OpenCV_LIBS}
        ${Sophus_LIBRARIES})

        
add_executable( 3d2d_g2o 3d2d_g2o.cpp )


target_link_libraries( 3d2d_g2o 
   ${OpenCV_LIBS}
   ${CSPARSE_LIBRARY}
   ${Sophus_LIBRARIES}
   g2o_core g2o_stuff g2o_types_sba g2o_csparse_extension
)

add_executable( pose_estimation_3d3d pose_estimation_3d3d.cpp )
target_link_libraries( pose_estimation_3d3d 
   ${OpenCV_LIBS}
   ${Sophus_LIBRARIES}
   ${CSPARSE_LIBRARY}
   g2o_core g2o_stuff g2o_types_sba g2o_csparse_extension
)

add_executable( 3d3d 3d3d.cpp )
target_link_libraries( 3d3d 
   ${OpenCV_LIBS}
   ${Sophus_LIBRARIES}
   ${CSPARSE_LIBRARY}
   g2o_core g2o_stuff g2o_types_sba g2o_csparse_extension
)



头文件

#include <opencv2/highgui/highgui.hpp>
#include <opencv2/calib3d/calib3d.hpp>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <Eigen/SVD>
#include <g2o/core/base_vertex.h>
#include <g2o/core/base_unary_edge.h>
#include <g2o/core/block_solver.h>
#include <g2o/core/optimization_algorithm_gauss_newton.h>
#include <g2o/solvers/eigen/linear_solver_eigen.h>
#include <g2o/types/sba/types_six_dof_expmap.h>
#include <chrono>
#include "opencv2/imgcodecs/legacy/constants_c.h"
#include "sophus/se3.h"
#include "sophus/so3.h"

结果分析

分析结果可以发现,利用G2O只迭代一次后误差就基本不变了,也就是说算法一开始就已经收敛,所以可以把SVD(不经过迭代优化)得到的位姿值看为相机位姿的最优值。

  • 4
    点赞
  • 10
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

隔壁老王的学习日志

创作不易、球球大家打赏一下~

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值