在上一篇文章中,我们介绍了3D-2D相机位姿估计,采用PnP方法估计单目SLAM的相机位姿。而对于RGBD深度相机来说,每张图片都有深度信息,如果还用PnP方法,就无法充分利用已知的信息。因此,本文将介绍专门用于3D-3D相机位姿估计的方法。
从两组3D点中恢复出相机位姿信息的方法通常称为迭代最近点(Iterative Closest Point,ICP)。和PnP类似,ICP的求解也分为两种方式:利用线性代数求解(SVD方法)以及利用非线性优化方式求解(类似于Bundle Adjustment)。下面分别介绍。
一、SVD方法
SVD方法直接根据3D点的坐标,通过数学推导,利用一次SVD分解,即可给出旋转矩阵R和平移矩阵t的结果。具体的推导建议看教材,这里说也说不清楚,所以只给出思路和实现代码。
下面代码中的pose_estimation_3d3d
函数输入两组3D点的坐标,输出旋转矩阵R和平移矩阵t。中间用到了一次SVD分解。
void pose_estimation_3d3d (
const vector& pts1,
const vector& pts2,
Mat& R, Mat& t
)
{
Point3f p1, p2; // center of mass
int N = pts1.size();
for ( int i=0; i q1 ( N ), q2 ( N ); // remove the center
for ( int i=0; i svd ( W, Eigen::ComputeFullU|Eigen::ComputeFullV );
Eigen::Matrix3d U = svd.matrixU();
Eigen::Matrix3d V = svd.matrixV();
cout<<"U="< ( 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_ ( 3,1 ) << t_ ( 0,0 ), t_ ( 1,0 ), t_ ( 2,0 ) );
}
二、非线性优化方法
仍然是构造一个图优化问题,这里我们把相机位姿作为优化变量,3D点对之间的坐标变换作为误差项。由于g2o没有为我们提供3D到3D的边,因此需要我们自己来定义。这是一个一元边,观测量即3D点的维度为3,代码如下所示。
// 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 ( _vertices[0] );
// measurement is p, point is p'
_error = _measurement - pose->estimate().map( _point );
}
virtual void linearizeOplus()
{
g2o::VertexSE3Expmap* pose = static_cast(_vertices[0]);
g2o::SE3Quat T(pose->estimate());
Eigen::Vector3d xyz_trans = T.map(_point);
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* 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 edges;
for ( size_t i=0; isetId( index );
edge->setVertex( 0, dynamic_cast (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(10);
chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
chrono::duration time_used = chrono::duration_cast>(t2-t1);
cout<<"optimization costs time: "<estimate() ).matrix()<
这个非线性优化问题似乎显得有些乏味,只对一个相机位姿进行优化,并不能体现出优化的效果。如果我们把两组3D点的坐标也作为优化变量加入图优化,也许会更有意思,不过就不在这里讨论了。
完整代码见GitHub:https://github.com/jingedawang/FeatureMethod
三、参考资料
《视觉SLAM十四讲》第7讲 视觉里程计1 高翔