第七讲:视觉里程计3
4 3D - 3D ICP
一组配对好的3D点(例如我们对两幅RGB-D图像进行了匹配):
P
=
{
p
1
,
⋯
,
p
n
}
,
P
′
=
{
p
1
′
,
⋯
,
p
n
′
}
\boldsymbol{P}=\left\{\boldsymbol{p}_1, \cdots, \boldsymbol{p}_n\right\}, \quad \boldsymbol{P}^{\prime}=\left\{\boldsymbol{p}_1^{\prime}, \cdots, \boldsymbol{p}_n^{\prime}\right\}
P={p1,⋯,pn},P′={p1′,⋯,pn′}
求解一个欧式变换R,t
∀
i
,
p
i
=
R
p
i
′
+
t
\forall i, \boldsymbol{p}_i=\boldsymbol{R} \boldsymbol{p}_i^{\prime}+\boldsymbol{t}
∀i,pi=Rpi′+t
ICP,即迭代最近点(Iterative Closest Point)求解。3D-3D位姿估计问题中并没有出现相机模型,也就是说,仅考虑两组3D点之间的变换时,和相机并没有关系。因此,在激光SLAM中也会碰到ICP,不过由于激光数据特征不够丰富,我们无从知道两个点集之间的匹配关系,只能认为距离最近的两个点为同一个,所以这个方法称为迭代最近点。
在V-SLAM中,我们可以很容易得到一组匹配好的特征点。在RGB-D SLAM中,可以用这种方式估计相机位姿。
ICP的求解也分为两种方式:
1. 利用线性代数的求解(主要是SVD)
2. 利用非线性优化方式的求解(类似于BA)。下面分别进行介绍。
4.1 SVD分解
我们要求最优解,还是要构建误差函数公式,利用非线性最小二乘法来求解。当然,SVD中利用了线性方程组的化简技巧,不会像第二种方法一样直接去求导。
第i组匹配的特征点误差为:
e
i
=
p
i
−
(
R
p
i
′
+
t
)
\boldsymbol{e}_i=\boldsymbol{p}_i-\left(\boldsymbol{R} \boldsymbol{p}_i^{\prime}+\boldsymbol{t}\right)
ei=pi−(Rpi′+t)
构建最小二乘问题,求出使得平方和最小的位姿T:
min
R
,
t
1
2
∑
i
=
1
n
∥
(
p
i
−
(
R
p
i
′
+
t
)
)
∥
2
2
\min _{\boldsymbol{R}, t} \frac{1}{2} \sum_{i=1}^n\left\|\left(\boldsymbol{p}_i-\left(\boldsymbol{R} \boldsymbol{p}_i{ }^{\prime}+\boldsymbol{t}\right)\right)\right\|_2^2
R,tmin21i=1∑n∥(pi−(Rpi′+t))∥22
基于SVD的ICP法定义了关于求解特征点组的质心(即图像的位置质心):
p
=
1
n
∑
i
=
1
n
(
p
i
)
,
p
′
=
1
n
∑
i
=
1
n
(
p
i
′
)
\boldsymbol{p}=\frac{1}{n} \sum_{i=1}^n\left(\boldsymbol{p}_i\right), \quad \boldsymbol{p}^{\prime}=\frac{1}{n} \sum_{i=1}^n\left(\boldsymbol{p}_i^{\prime}\right)
p=n1i=1∑n(pi),p′=n1i=1∑n(pi′)
对上面最小二乘法进行推导,实际上就是一个去质心的过程
1
2
∑
i
=
1
n
∥
p
i
−
(
R
p
i
′
+
t
)
∥
2
=
1
2
∑
i
=
1
n
∥
p
i
−
R
p
i
′
−
t
−
p
+
R
p
′
+
p
−
R
p
′
∥
2
=
1
2
∑
i
=
1
n
∥
(
p
i
−
p
−
R
(
p
i
′
−
p
′
)
)
+
(
p
−
R
p
′
−
t
)
∥
2
=
1
2
∑
i
=
1
n
(
∥
p
i
−
p
−
R
(
p
i
′
−
p
′
)
∥
2
+
∥
p
−
R
p
′
−
t
∥
2
+
2
(
p
i
−
p
−
R
(
p
i
′
−
p
′
)
)
T
(
p
−
R
p
′
−
t
)
)
.
\begin{aligned} \frac{1}{2} \sum_{i=1}^n\left\|\boldsymbol{p}_i-\left(\boldsymbol{R} \boldsymbol{p}_i{ }^{\prime}+\boldsymbol{t}\right)\right\|^2= & \frac{1}{2} \sum_{i=1}^n\left\|\boldsymbol{p}_i-\boldsymbol{R} \boldsymbol{p}_i{ }^{\prime}-\boldsymbol{t}-\boldsymbol{p}+\boldsymbol{R} \boldsymbol{p}^{\prime}+\boldsymbol{p}-\boldsymbol{R} \boldsymbol{p}^{\prime}\right\|^2 \\ = & \frac{1}{2} \sum_{i=1}^n\left\|\left(\boldsymbol{p}_i-\boldsymbol{p}-\boldsymbol{R}\left(\boldsymbol{p}_i{ }^{\prime}-\boldsymbol{p}^{\prime}\right)\right)+\left(\boldsymbol{p}-\boldsymbol{R} \boldsymbol{p}^{\prime}-\boldsymbol{t}\right)\right\|^2 \\ = & \frac{1}{2} \sum_{i=1}^n\left(\left\|\boldsymbol{p}_i-\boldsymbol{p}-\boldsymbol{R}\left(\boldsymbol{p}_i{ }^{\prime}-\boldsymbol{p}^{\prime}\right)\right\|^2+\left\|\boldsymbol{p}-\boldsymbol{R} \boldsymbol{p}^{\prime}-\boldsymbol{t}\right\|^2+\right. \\ & \left.2\left(\boldsymbol{p}_i-\boldsymbol{p}-\boldsymbol{R}\left(\boldsymbol{p}_i{ }^{\prime}-\boldsymbol{p}^{\prime}\right)\right)^{\mathrm{T}}\left(\boldsymbol{p}-\boldsymbol{R} \boldsymbol{p}^{\prime}-\boldsymbol{t}\right)\right) . \end{aligned}
21i=1∑n∥pi−(Rpi′+t)∥2===21i=1∑n∥pi−Rpi′−t−p+Rp′+p−Rp′∥221i=1∑n∥(pi−p−R(pi′−p′))+(p−Rp′−t)∥221i=1∑n(∥pi−p−R(pi′−p′)∥2+∥p−Rp′−t∥2+2(pi−p−R(pi′−p′))T(p−Rp′−t)).
后面一项求和之后为0(还没有推出),所以我们就可以简化得到下面这个式子
min
R
,
t
J
=
1
2
∑
i
=
1
n
∥
p
i
−
p
−
R
(
p
i
′
−
p
′
)
∥
2
+
∥
p
−
R
p
′
−
t
∥
2
\min _{\boldsymbol{R}, t} J=\frac{1}{2} \sum_{i=1}^n\left\|\boldsymbol{p}_i-\boldsymbol{p}-\boldsymbol{R}\left(\boldsymbol{p}_i{ }^{\prime}-\boldsymbol{p}^{\prime}\right)\right\|^2+\left\|\boldsymbol{p}-\boldsymbol{R} \boldsymbol{p}^{\prime}-\boldsymbol{t}\right\|^2
R,tminJ=21i=1∑n∥pi−p−R(pi′−p′)∥2+∥p−Rp′−t∥2
我们把它写成去质心的形式,即(而且上面式子可以先求左边最小值,且令右边式子为0,这样子和也是求得最小值情况下的位姿T。这里主要是平方项,最小就是0,而且左边式子还与t无关,所以这样子求解方程是没有问题的。):
R ∗ = arg min R 1 2 ∑ i = 1 n ∥ q i − R q i ′ ∥ 2 \boldsymbol{R}^*=\arg \min _{\boldsymbol{R}} \frac{1}{2} \sum_{i=1}^n\left\|\boldsymbol{q}_i-\boldsymbol{R} \boldsymbol{q}_i^{\prime}\right\|^2 R∗=argRmin21i=1∑n∥qi−Rqi′∥2
t ∗ = p − R p ′ t^*=p-R p^{\prime} t∗=p−Rp′
注意,q是去质心坐标
q
i
=
p
i
−
p
,
q
i
′
=
p
i
′
−
p
′
\boldsymbol{q}_i=\boldsymbol{p}_i-\boldsymbol{p}, \quad \boldsymbol{q}_i^{\prime}=\boldsymbol{p}_i^{\prime}-\boldsymbol{p}^{\prime}
qi=pi−p,qi′=pi′−p′
根据上面的推理,我们只需要优化R那个等式
1
2
∑
i
=
1
n
∥
q
i
−
R
q
i
′
∥
2
=
1
2
∑
i
=
1
n
(
q
i
T
q
i
+
q
i
′
T
R
T
R
q
i
′
−
2
q
i
T
R
q
i
′
)
\frac{1}{2} \sum_{i=1}^n\left\|\boldsymbol{q}_i-\boldsymbol{R} \boldsymbol{q}_i^{\prime}\right\|^2=\frac{1}{2} \sum_{i=1}^n\left(\boldsymbol{q}_i^{\mathrm{T}} \boldsymbol{q}_i+\boldsymbol{q}_i^{\prime \mathrm{T}} \boldsymbol{R}^{\mathrm{T}} \boldsymbol{R} \boldsymbol{q}_i^{\prime}-2 \boldsymbol{q}_i^{\mathrm{T}} \boldsymbol{R} \boldsymbol{q}_i^{\prime}\right)
21i=1∑n∥qi−Rqi′∥2=21i=1∑n(qiTqi+qi′TRTRqi′−2qiTRqi′)
展开后我们就会发现,其中前面两项与R无关(**RR^T = I正交矩阵的特点),那么我们就只需要优化下面的式子
∑
i
=
1
n
−
q
i
T
R
q
i
′
=
∑
i
=
1
n
−
tr
(
R
q
i
′
q
i
T
)
=
−
tr
(
R
∑
i
=
1
n
q
i
′
q
i
T
)
\sum_{i=1}^n-\boldsymbol{q}_i^{\mathrm{T}} \boldsymbol{R} \boldsymbol{q}_i^{\prime}=\sum_{i=1}^n-\operatorname{tr}\left(\boldsymbol{R} \boldsymbol{q}_i^{\prime} \boldsymbol{q}_i^{\mathrm{T}}\right)=-\operatorname{tr}\left(\boldsymbol{R} \sum_{i=1}^n \boldsymbol{q}_i^{\prime} \boldsymbol{q}_i^{\mathrm{T}}\right)
i=1∑n−qiTRqi′=i=1∑n−tr(Rqi′qiT)=−tr(Ri=1∑nqi′qiT)
这个时候就用到SVD分解**了。其中,∑为奇异值组成的对角矩阵,对角线元素从大到小排列,而U和V为对角矩阵。W是3*3矩阵
W
=
∑
i
=
1
n
q
i
q
i
′
T
\boldsymbol{W}=\sum_{i=1}^n \boldsymbol{q}_i \boldsymbol{q}_i^{\prime \mathrm{T}}
W=i=1∑nqiqi′T
W = U Σ V T \boldsymbol{W}=\boldsymbol{U} \boldsymbol{\Sigma} \boldsymbol{V}^{\mathrm{T}} W=UΣVT
最终,R和t的计算式子如下
R
=
U
V
T
\boldsymbol{R}=\boldsymbol{U} \boldsymbol{V}^{\mathrm{T}}
R=UVT
t ∗ = p − R p ′ t^*=p-R p^{\prime} t∗=p−Rp′
4.2 非线性优化
目标函数:
min
ξ
=
1
2
∑
i
=
1
n
∥
(
p
i
−
exp
(
ξ
∧
)
p
i
′
)
∥
2
2
\min _{\boldsymbol{\xi}}=\frac{1}{2} \sum_{i=1}^n\left\|\left(\boldsymbol{p}_i-\exp \left(\boldsymbol{\xi}^{\wedge}\right) \boldsymbol{p}_i^{\prime}\right)\right\|_2^2
ξmin=21i=1∑n
(pi−exp(ξ∧)pi′)
22
∂ e ∂ δ ξ = − ( exp ( ξ ∧ ) p i ′ ) ⊙ \frac{\partial \boldsymbol{e}}{\partial \delta \boldsymbol{\xi}}=-\left(\exp \left(\boldsymbol{\xi}^{\wedge}\right) \boldsymbol{p}_i^{\prime}\right)^{\odot} ∂δξ∂e=−(exp(ξ∧)pi′)⊙
4.3 ICP总结
ICP问题存在唯一解或无穷多解的情况。在唯一解的情况下,只要能找到极小值解,这个极小值就是全局最优值(因此不会遇到局部极小而非全局最小的情况)。这也意味着ICP求解可以任意选定初始值。这是已匹配点时求解ICP的一大好处。
4.4 实验程序
- pose_estimation_ 3 d 3 d
#include <iostream>
#include <opencv2/core/core.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/calib3d/calib3d.hpp>
#include <Eigen/Core>
#include <Eigen/Dense>
#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/core/optimization_algorithm_levenberg.h>
#include <g2o/solvers/dense/linear_solver_dense.h>
#include <chrono>
#include <sophus/se3.hpp>
using namespace std;
using namespace cv;
// 1. 寻找特征点并匹配
void find_feature_matches(
const Mat &img_1, const Mat &img_2,
std::vector<KeyPoint> &keypoints_1,
std::vector<KeyPoint> &keypoints_2,
std::vector<DMatch> &matches);
// 2. 像素坐标转相机归一化坐标
Point2d pixel2cam(const Point2d &p, const Mat &K);
// 3. ICP求解最优位姿T
void pose_estimation_3d3d(
const vector<Point3f> &pts1,
const vector<Point3f> &pts2,
Mat &R, Mat &t
);
// 4. BA优化 最小化重投影 PnP
void bundleAdjustment(
const vector<Point3f> &points_3d,
const vector<Point3f> &points_2d,
Mat &R, Mat &t
);
// 5. 顶点:优化参数 se(3) 6维
class VertexPose : public g2o::BaseVertex<6, Sophus::SE3d> {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
virtual void setToOriginImpl() override {
_estimate = Sophus::SE3d();
}
/// 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::SE3d::exp(update_eigen) * _estimate;
}
virtual bool read(istream &in) override {}
virtual bool write(ostream &out) const override {}
};
/// 6. g2o edge 误差维度3 x,y,z
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() override {
const VertexPose *pose = static_cast<const VertexPose *> ( _vertices[0] );
_error = _measurement - pose->estimate() * _point;
}
virtual void linearizeOplus() override {
VertexPose *pose = static_cast<VertexPose *>(_vertices[0]);
Sophus::SE3d T = pose->estimate();
Eigen::Vector3d xyz_trans = T * _point;
_jacobianOplusXi.block<3, 3>(0, 0) = -Eigen::Matrix3d::Identity();
_jacobianOplusXi.block<3, 3>(0, 3) = Sophus::SO3d::hat(xyz_trans);
}
bool read(istream &in) {}
bool write(ostream &out) const {}
protected:
Eigen::Vector3d _point;
};
int main(int argc, char **argv) {
if (argc != 5) {
cout << "usage: pose_estimation_3d3d img1 img2 depth1 depth2" << endl;
return 1;
}
//-- 读取图像
Mat img_1 = imread(argv[1], CV_LOAD_IMAGE_COLOR);
Mat img_2 = imread(argv[2], CV_LOAD_IMAGE_COLOR);
vector<KeyPoint> keypoints_1, keypoints_2;
vector<DMatch> matches;
find_feature_matches(img_1, img_2, keypoints_1, keypoints_2, matches);
cout << "一共找到了" << matches.size() << "组匹配点" << endl;
// 建立3D点
Mat depth1 = imread(argv[3], CV_LOAD_IMAGE_UNCHANGED); // 深度图为16位无符号数,单通道图像
Mat depth2 = imread(argv[4], CV_LOAD_IMAGE_UNCHANGED); // 深度图为16位无符号数,单通道图像
Mat K = (Mat_<double>(3, 3) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1);
vector<Point3f> pts1, pts2;
for (DMatch m:matches) {
ushort d1 = depth1.ptr<unsigned short>(int(keypoints_1[m.queryIdx].pt.y))[int(keypoints_1[m.queryIdx].pt.x)];
ushort d2 = depth2.ptr<unsigned short>(int(keypoints_2[m.trainIdx].pt.y))[int(keypoints_2[m.trainIdx].pt.x)];
if (d1 == 0 || d2 == 0) // bad depth
continue;
Point2d p1 = pixel2cam(keypoints_1[m.queryIdx].pt, K);
Point2d p2 = pixel2cam(keypoints_2[m.trainIdx].pt, K);
float dd1 = float(d1) / 5000.0;
float dd2 = float(d2) / 5000.0;
pts1.push_back(Point3f(p1.x * dd1, p1.y * dd1, dd1));
pts2.push_back(Point3f(p2.x * dd2, p2.y * dd2, dd2));
}
cout << "3d-3d pairs: " << pts1.size() << endl;
Mat R, t;
// 这里调用ICP函数求解
pose_estimation_3d3d(pts1, pts2, R, t);
cout << "ICP via SVD results: " << endl;
cout << "R = " << R << endl;
cout << "t = " << t << endl;
cout << "R_inv = " << R.t() << endl;
cout << "t_inv = " << -R.t() * t << endl;
cout << "calling bundle adjustment" << endl;
// 最优化求解
bundleAdjustment(pts1, pts2, R, t);
// verify p1 = R * p2 + t
for (int i = 0; i < 5; i++) {
cout << "p1 = " << pts1[i] << endl;
cout << "p2 = " << pts2[i] << endl;
cout << "(R*p2+t) = " <<
R * (Mat_<double>(3, 1) << pts2[i].x, pts2[i].y, pts2[i].z) + t
<< endl;
cout << endl;
}
}
void find_feature_matches(const Mat &img_1, const Mat &img_2,
std::vector<KeyPoint> &keypoints_1,
std::vector<KeyPoint> &keypoints_2,
std::vector<DMatch> &matches) {
//-- 初始化
Mat descriptors_1, descriptors_2;
// used in OpenCV3
Ptr<FeatureDetector> detector = ORB::create();
Ptr<DescriptorExtractor> descriptor = ORB::create();
// use this if you are in OpenCV2
// Ptr<FeatureDetector> detector = FeatureDetector::create ( "ORB" );
// Ptr<DescriptorExtractor> descriptor = DescriptorExtractor::create ( "ORB" );
Ptr<DescriptorMatcher> matcher = DescriptorMatcher::create("BruteForce-Hamming");
//-- 第一步:检测 Oriented FAST 角点位置
detector->detect(img_1, keypoints_1);
detector->detect(img_2, keypoints_2);
//-- 第二步:根据角点位置计算 BRIEF 描述子
descriptor->compute(img_1, keypoints_1, descriptors_1);
descriptor->compute(img_2, keypoints_2, descriptors_2);
//-- 第三步:对两幅图像中的BRIEF描述子进行匹配,使用 Hamming 距离
vector<DMatch> match;
// BFMatcher matcher ( NORM_HAMMING );
matcher->match(descriptors_1, descriptors_2, match);
//-- 第四步:匹配点对筛选
double min_dist = 10000, max_dist = 0;
//找出所有匹配之间的最小距离和最大距离, 即是最相似的和最不相似的两组点之间的距离
for (int i = 0; i < descriptors_1.rows; i++) {
double dist = match[i].distance;
if (dist < min_dist) min_dist = dist;
if (dist > max_dist) max_dist = dist;
}
printf("-- Max dist : %f \n", max_dist);
printf("-- Min dist : %f \n", min_dist);
//当描述子之间的距离大于两倍的最小距离时,即认为匹配有误.但有时候最小距离会非常小,设置一个经验值30作为下限.
for (int i = 0; i < descriptors_1.rows; i++) {
if (match[i].distance <= max(2 * min_dist, 30.0)) {
matches.push_back(match[i]);
}
}
}
Point2d pixel2cam(const Point2d &p, const Mat &K) {
return Point2d(
(p.x - K.at<double>(0, 2)) / K.at<double>(0, 0),
(p.y - K.at<double>(1, 2)) / K.at<double>(1, 1)
);
}
// ICP 本程序重点 未调用库
void pose_estimation_3d3d(const vector<Point3f> &pts1,
const vector<Point3f> &pts2,
Mat &R, Mat &t) {
Point3f p1, p2; // 定义质心
int N = pts1.size();
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;
}
// 计算 q1*q2^T
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
Eigen::JacobiSVD<Eigen::Matrix3d> svd(W, Eigen::ComputeFullU | Eigen::ComputeFullV);
Eigen::Matrix3d U = svd.matrixU();
Eigen::Matrix3d V = svd.matrixV();
cout << "U=" << U << endl;
cout << "V=" << V << endl;
Eigen::Matrix3d R_ = U * (V.transpose());
if (R_.determinant() < 0) {
R_ = -R_;
}
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));
}
void bundleAdjustment(
const vector<Point3f> &pts1,
const vector<Point3f> &pts2,
Mat &R, Mat &t) {
// 构建图优化,先设定g2o
typedef g2o::BlockSolverX BlockSolverType;
typedef g2o::LinearSolverDense<BlockSolverType::PoseMatrixType> LinearSolverType; // 线性求解器类型
// 梯度下降方法,可以从GN, LM, DogLeg 中选
auto solver = new g2o::OptimizationAlgorithmLevenberg(
g2o::make_unique<BlockSolverType>(g2o::make_unique<LinearSolverType>()));
g2o::SparseOptimizer optimizer; // 图模型
optimizer.setAlgorithm(solver); // 设置求解器
optimizer.setVerbose(true); // 打开调试输出
// vertex
VertexPose *pose = new VertexPose(); // camera pose
pose->setId(0);
pose->setEstimate(Sophus::SE3d());
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.initializeOptimization();
optimizer.optimize(10);
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=\n" << pose->estimate().matrix() << endl;
// convert to cv::Mat
Eigen::Matrix3d R_ = pose->estimate().rotationMatrix();
Eigen::Vector3d t_ = pose->estimate().translation();
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));
}