一、LK 光流
1.1 光流文献综述
我们课上演示了 Lucas-Kanade 稀疏光流,用 OpenCV 函数实现了光流法追踪特征点。实际上,光流 法有很长时间的研究历史,直到现在人们还在尝试用 Deep learning 等方法对光流进行改进 [1, 2]。本题将 指导你完成基于 Gauss-Newton 的金字塔光流法。首先,请阅读文献 [3](paper 目录下提供了 pdf),回答 下列问题。
问题:
按此文的分类,光流法可分为哪几类?
可以分4类,在Image Alignment上,分别是 FA(Forward Additional), FC(Forward Composition), **IA(Inverse Additional) **和 IC(Inverse Compositional)。
在 compositional 中,为什么有时候需要做原始图像的 warp?该 warp有何物理意义?
Forward 方法:
与Lucas-Kanade算法中简单地向参数 p 的当前估计数中添加附加的更新增量 \Delta p 不同,对 warp(W_{(x;\Delta p)}) 的增量更新必须与Compositional Algorithm中的 warp(W_{(x;p)}) 的当前估计数相结合。这种操作通常涉及将两个矩阵相乘来计算组合变形的参数,如仿射变换。对于更复杂的 warp,这两个 warp 的组合可能更复杂。因此,我们对 warp 集合有两个要求: 1)warp 集合必须包含 identity warp。2)**warp **集合必须在组合运算中闭合。这组 warp 必须是 semi-group。在计算机视觉中使用的大多数 warp,包括单应变换和3D旋转都是 semi-group。
warp 的物理意义是仿射变换 ,矩阵形式是 T=\begin{bmatrix}A & t\\ 0^T & 1 \end{bmatrix} ,其中A 为可逆矩阵。
forward 和 inverse 有何差别?
前向方法对于输入图像进行参数化(包括仿射变换及放射增量)。后向方法则同时参数输入图像和模板图像,其中输入图像参数化仿射变换,模板图像参数参数化仿射增量。因此后向方法的计算量显著降低,由于图像灰度值和运动参数非线性,整个优化过程为非线性的。
1.2 forward-addtive Gauss-Newton 光流的实现
接下来我们来实现最简单的光流,即上文所说的 forward-addtive。我们先考虑单层图像的 LK 光流, 然后再推广至金字塔图像。按照教材的习惯,我们把光流法建模成一个非线性优化问题,再使用 Gauss-Newton 法迭代求解。设有图像 1.png,2.png,我们在 1.png 中提取了 GFTT 角点,然后希望在 2.png 中追踪这些关键点。设两个图分别为 I_1,I_2,第一张图中提取的点集为 P = {p_i},其中 p_i = [x_i,y_i]^T 为像素坐标值。考虑第 i 个点,我们希望计算 ∆x_i,∆y_i,满足:
\underset{\Delta x_i,\Delta y_i}{\min} \underset{W}{\sum}||I_1(x_i,y_i)-I_2(x_i+\Delta x_i, y_i + \Delta y_i)||_2^2
即最小化二者灰度差的平方,其中 \underset{W}{\sum} 表示我们在某个窗口(Window)中求和(而不是单个像素,因为问题有两个未知量,单个像素只有一个约束,是欠定的)。实践中,取此 window 为 8×8 大小的小块,即 从 x_i − 4 取到 x_i + 3,y 坐标亦然。显然,这是一个 forward-addtive 的光流,而上述最小二乘问题可以 用 Gauss-Newton 迭代求解。请回答下列问题,并根据你的回答,实现 code/optical_flow.cpp 文件中的 OpticalFlowSingleLevel 函数。
- 从最小二乘角度来看,每个像素的误差怎么定义?
- 误差相对于自变量的导数如何定义?
下面是有关实现过程中的一些提示:
- 同上一次作业,你仍然需要去除那些提在图像边界附近的点,不然你的图像块可能越过边界。
- 该函数称为单层的光流,下面我们要基于这个函数来实现多层的光流。在主函数中,我们对两张图 像分别测试单层光流、多层光流,并与 OpenCV 结果进行对比。作为验证,正向单层光流结果应 该如图 1 所示,它结果不是很好,但大部分还是对的。
- 在光流中,关键点的坐标值通常是浮点数,但图像数据都是以整数作为下标的。之前我们直接取了 浮点数的整数部分,即把小数部分归零。但是在光流中,通常的优化值都在几个像素内变化,所以 我们还用浮点数的像素插值。函数 GetPixelValue 为你提供了一个双线性插值方法(这也是常用的 图像插值法之一),你可以用它来获得浮点的像素值。
OpticalFlowSingleLevel 代码:
OpticalFlowSingleLevel(img1, img2, kp1, kp2_single, success_single);
void OpticalFlowSingleLevel(
const Mat &img1,
const Mat &img2,
const vector<KeyPoint> &kp1,
vector<KeyPoint> &kp2,
vector<bool> &success,
bool inverse
) {
// parameters
int half_patch_size = 4;
int iterations = 10;
bool have_initial = !kp2.empty();
for (size_t i = 0; i < kp1.size(); i++) {
auto kp = kp1[i];
double dx = 0, dy = 0; // dx,dy need to be estimated
if (have_initial) {
dx = kp2[i].pt.x - kp.pt.x;
dy = kp2[i].pt.y - kp.pt.y;
}
double cost = 0, lastCost = 0;
bool succ = true; // indicate if this point succeeded
// Gauss-Newton iterations
for (int iter = 0; iter < iterations; iter++) {
Eigen::Matrix2d H = Eigen::Matrix2d::Zero();
Eigen::Vector2d b = Eigen::Vector2d::Zero();
cost = 0;
if (kp.pt.x + dx <= half_patch_size || kp.pt.x + dx >= img1.cols - half_patch_size ||
kp.pt.y + dy <= half_patch_size || kp.pt.y + dy >= img1.rows - half_patch_size) { // go outside
succ = false;
break;
}
// compute cost and jacobian
for (int x = -half_patch_size; x < half_patch_size; x++)
for (int y = -half_patch_size; y < half_patch_size; y++) {
// TODO START YOUR CODE HERE (~8 lines)
double error = 0;
Eigen::Vector2d J; // Jacobian
float u1 = float(kp.pt.x + x), v1 = float(kp.pt.y + y);
float u2 = float(u1 + dx), v2 = float(v1 + dy);
if (inverse == false) {
// Forward Jacobian
J(0,0) = 0.5*GetPixelValue(img2, u2 + 1, v2) - GetPixelValue(img2, u2 - 1, v2));
J(1,0) = 0.5*(GetPixelValue(img2, u2, v2 + 1) - GetPixelValue(img2, u2, v2 - 1));
error = GetPixelValue(img2, u2, v2) - GetPixelValue(img1, u1, v1);
} else {
// Inverse Jacobian
// NOTE this J does not change when dx, dy is updated, so we can store it and only compute error
J(0,0) = 0.5*(GetPixelValue(img1, u1 + 1, v1) - GetPixelValue(img1, u1 - 1, v1));
J(1,0) = 0.5*(GetPixelValue(img1, u1, v1 + 1) - GetPixelValue(img1, u1, v1 - 1));
error = GetPixelValue(img2, u2, v2) - GetPixelValue(img1, u1, v1);
}
// compute H, b and set cost;
H += J*J.transpose();
b += -J*error;
cost;
// TODO END YOUR CODE HERE
}
// compute update
// TODO START YOUR CODE HERE (~1 lines)
Eigen::Vector2d update;
update = H.ldlt().solve(b);
// TODO END YOUR CODE HERE
if (isnan(update[0])) {
// sometimes occurred when we have a black or white patch and H is irreversible
cout << "update is nan" << endl;
succ = false;
break;
}
if (iter > 0 && cost > lastCost) {
cout << "cost increased: " << cost << ", " << lastCost << endl;
break;
}
// update dx, dy
dx += update[0];
dy += update[1];
lastCost = cost;
succ = true;
}
success.push_back(succ);
// set kp2
if (have_initial) {
kp2[i].pt = kp.pt + Point2f(dx, dy);
} else {
KeyPoint tracked = kp;
tracked.pt += cv::Point2f(dx, dy);
kp2.push_back(tracked);
}
}
}
result:
1.3 反向法
在你实现了上述算法之后,就会发现,在迭代开始时,Gauss-Newton 的计算依赖于 I_2 在 (x_i+∆x_i,y_i+ ∆y_i) 处的梯度信息。然而,角点提取算法仅保证了I_1(x_i,y_i) 处是角点(可以认为角度点存在明显梯度), 但对于 I_2,我们并没有办法假设 I_2 在 x_i,y_i 处亦有梯度,从而 Gauss-Newton 并不一定成立。反向的光流法(inverse)则做了一个巧妙的技巧,即用 I_1(x_i,y_i) 处的梯度,替换掉原本要计算的I_2(x_i+∆x_i,y_i +∆y_i) 的梯度。这样做的好处有:
• I_1(x_i,y_i) 是角点,梯度总有意义;
• I_1(x_i,y_i) 处的梯度不随迭代改变,所以只需计算一次,就可以在后续的迭代中一直使用,节省了大量计算时间。
我们为 OpticalFlowSingleLevel 函数添加一个 bool inverse 参数,指定要使用正常的算法还是反向的 算法。请你根据上述说明,完成反向的 LK 光流法。
OpticalFlowSingleLevel(img1, img2, kp1, kp2_single, success_single, true);
result:
1.4 推广至金字塔
通过实验可以看出光流法通常只能估计几个像素内的误差。如果初始估计不够好,或者图像运动太 大,光流法就无法得到有效的估计(不像特征点匹配那样)。但是,使用图像金字塔,可以让光流对图像运 动不那么敏感。下面请你使用缩放倍率为 2,共四层的图像金字塔,实现 coarse-to-fine 的 LK 光流。函数在OpticalFlowMultiLevel 中。
实现完成后,给出你的光流截图(正向、反向、金字塔正向、金字塔反向),可以和 OpenCV 作比较。 然后回答下列问题:
- 所谓 coarse-to-fine 是指怎样的过程?
- 光流法中的金字塔用途和特征点法中的金字塔有何差别? 提示:你可以使用上面写的单层光流来帮助你实现多层光流。
1.5 讨论
现在你已经自己实现了光流,看到了基于金字塔的 LK 光流能够与 OpenCV 达到相似的效果(甚至更好)。根据光流的结果,你可以和上讲一样,计算对极几何来估计相机运动。下面针对本次实验结果,谈谈你对下面问题的看法:
• 我们优化两个图像块的灰度之差真的合理吗?哪些时候不够合理?你有解决办法吗?
• 图像块大小是否有明显差异?取 16x16 和 8x8 的图像块会让结果发生变化吗?
• 金字塔层数对结果有怎样的影响?缩放倍率呢?
二、直接法
2.1 单层直接法
我们说直接法是光流的直观拓展。在光流中,我们估计的是每个像素的平移(在 additive 的情况下)。 而在直接法当中,我们最小化光流误差,来估计相机的旋转和平移(以李代数的形式)。现在我们将使用和 前一个习题非常相似的做法来实现直接法,请同学体现二者之间的紧密联系。
本习题中,你将使用 Kitti 数据集中的一些图像。给定 left.png 和 disparity.png,我们知道,通过这两个 图可以得到 left.png 中任意一点的 3D 信息。现在,请你使用直接法,估计图像 000001.png 至 000005.png 的相机位姿。我们称 left.png 为参考图像(reference,简称 ref),称 000001.png -000005.png 中任意一图 为当前图像(current,简称 cur),如图2 所示。设待估计的目标为 T_{cur,ref},那么在 ref 中取一组点 {p_i}, 位姿可以通过最小化下面的目标函数求解:
T_{cur,ref} = \frac{1}{N}\sum^{N}_{i = 1}\sum_{W_i}||I_{ref}(\pi(p_i)) - I_{cur}(\pi(T_{cur,ref}\:p_i)) ||^2_2
其中 N 为点数,π 函数为针孔相机的投影函数 R^3 →R^2,W_i 为第 i 个点周围的小窗口。同光流法,该问题 可由 Gauss-Newton 函数求解。请回答下列问题,然后实现 code/direct_method.cpp 中的 DirectPoseEstimationSingleLayer 函数。
- 该问题中的误差项是什么?
- 误差相对于自变量的雅可比维度是多少?如何求解?
- 窗口可以取多大?是否可以取单个点?
下面是一些实现过程中的提示:
- 这次我们在参考图像中随机取 1000 个点,而不是取角点。请思考为何不取角点,直接法也能工作。
- 由于相机运动,参考图像中的点可能在投影之后,跑到后续图像的外部。所以最后的目标函数要对 投影在内部的点求平均误差,而不是对所有点求平均。程序中我们以 good 标记出投影在内部的点。
- 单层直接法的效果不会很好,但是你可以查看每次迭代的目标函数都会下降.
DirectPoseEstimationSingleLayer 代码
void DirectPoseEstimationSingleLayer(
const cv::Mat &img1,
const cv::Mat &img2,
const VecVector2d &px_ref,
const vector<double> depth_ref,
Sophus::SE3 &T21
) {
// parameters
int half_patch_size = 4;
int iterations = 100;
double cost = 0, lastCost = 0;
int nGood = 0; // good projections
VecVector2d goodProjection;
for (int iter = 0; iter < iterations; iter++) {
nGood = 0;
goodProjection.clear();
// Define Hessian and bias
Matrix6d H = Matrix6d::Zero(); // 6x6 Hessian
Vector6d b = Vector6d::Zero(); // 6x1 bias
for (size_t i = 0; i < px_ref.size(); i++) {
// compute the projection in the second image
// TODO START YOUR CODE HERE
float u = px_ref[i][0], v = px_ref[i][1];
if (u <= half_patch_size || u >= img1.cols - half_patch_size ||
v <= half_patch_size || v >= img1.rows - half_patch_size) { // go outside
continue;
}
nGood++;
goodProjection.push_back(Eigen::Vector2d(u, v));
// and compute error and jacobian
for (int x = -half_patch_size; x < half_patch_size; x++)
for (int y = -half_patch_size; y < half_patch_size; y++) {
double error =0;
Matrix26d J_pixel_xi; // pixel to \xi in Lie algebra
Eigen::Vector2d J_img_pixel; // image gradients
float u1 = float(u + x), v1 = float(v + y);
Eigen::Vector3d pc1, pc2; // cam p1 and p2
pc1[2] = depth_ref[i]; //z
pc1[1] = double(pc1[2]*(v - cy)/fy); //y
pc1[0] = double(pc1[2]*(u - cx)/fx); //x
pc2 = T21*pc1; // T21 is the update variable
float u_21 = float(fx*pc2[0]/pc2[2] + cx), v_21 = float(fy*pc2[1]/pc2[2] + cy);
float u2 = float(u_21 + x), v2 = float(v_21 + y);
if (u2 + 1 < 0 || u2 - 1 >= img1.cols ||
v2 + 1 < 0 || v2 - 1 >= img1.rows ) { // go outside
continue;
}
// Forward Jacobian
J_img_pixel[0] = GetPixelValue(img2, u2 + 1, v2) - GetPixelValue(img2, u2 - 1, v2); // delta u
J_img_pixel[1] = GetPixelValue(img2, u2, v2 + 1) - GetPixelValue(img2, u2, v2 - 1); // delta v
error = GetPixelValue(img2, u2, v2) - GetPixelValue(img1, u1, v1);
double Z = pc2[2], X = pc2[0], Y = pc2[1]; //p195
J_pixel_xi(0,0) = fx/Z;
J_pixel_xi(0,2) = -fx*X/(Z*Z);
J_pixel_xi(0,3) = -fx*X*Y/(Z*Z);
J_pixel_xi(0,4) = fx + fx*X*X/(Z*Z);
J_pixel_xi(0,5) = -fx*Y/Z;
J_pixel_xi(1,1) = fy/Z;
J_pixel_xi(1,2) = -fy*Y/(Z*Z);
J_pixel_xi(1,3) = -fy - fy*Y*Y/(Z*Z);
J_pixel_xi(1,4) = fy*X*Y/(Z*Z);
J_pixel_xi(1,5) = fy*X/Z;
// total jacobian
Vector6d J= -J_pixel_xi.transpose()*J_img_pixel;
H += J * J.transpose();
b += -error * J;
cost += error * error;
}
// END YOUR CODE HERE
}
// solve update and put it into estimation
// TODO START YOUR CODE HERE
Vector6d update;
update = H.ldlt().solve(b);
T21 = Sophus::SE3::exp(update) * T21;
// END YOUR CODE HERE
cost /= nGood;
if (isnan(update[0])) {
// sometimes occurred when we have a black or white patch and H is irreversible
cout << "update is nan" << endl;
break;
}
if (iter > 0 && cost > lastCost) {
cout << "cost increased: " << cost << ", " << lastCost << endl;
break;
}
lastCost = cost;
cout << "cost = " << cost << ", good = " << nGood << endl;
}
cout << "good projection: " << nGood << endl;
cout << "T21 = \n" << T21.matrix() << endl;
// in order to help you debug, we plot the projected pixels here
cv::Mat img1_show, img2_show;
cv::cvtColor(img1, img1_show, CV_GRAY2BGR);
cv::cvtColor(img2, img2_show, CV_GRAY2BGR);
for (auto &px: px_ref) {
cv::rectangle(img1_show, cv::Point2f(px[0] - 2, px[1] - 2), cv::Point2f(px[0] + 2, px[1] + 2),
cv::Scalar(0, 250, 0));
}
for (auto &px: goodProjection) {
cv::rectangle(img2_show, cv::Point2f(px[0] - 2, px[1] - 2), cv::Point2f(px[0] + 2, px[1] + 2),
cv::Scalar(0, 250, 0));
}
cv::imshow("reference", img1_show);
cv::imshow("current", img2_show);
cv::waitKey();
}
2.2 多层直接法
下面,类似于光流,我们也可以把直接法以 coarse-to-fine 的过程,拓展至多层金字塔。多层金字塔的 直接法允许图像在发生较大运动时仍能追踪到所有点。下面我们使用缩放倍率为 2 的四层金字塔,实现金 字塔上的直接法。请实现 DirectPoseEstimationMultiLayer 函数,下面是一些提示:
在缩放图像时,图像内参也需要跟着变化。那么,例如图像缩小一倍,f_x,f_y,c_x,c_y 应该如何变化?
根据 coarse-to-fine 的过程,上一层图像的位姿估计结果可以作为下一层图像的初始条件。
在调试期间,可以画出每个点在 ref 和 cur 上的投影,看看它们是否对应。若准确对应,则说明位 姿估计是准确的。 作为验证,图像 000001 和 000005 的位姿平移部分应该接近:
\begin{aligned} t_1 &= [0.005876,−0.01024,−0.725]^T \\ t_5 &= [0.0394,−0.0592,−3.9907]^T \end{aligned}
可以看出车辆基本是笔直向前开的。
DirectPoseEstimationMultiLayer 代码
void DirectPoseEstimationMultiLayer(
const cv::Mat &img1,
const cv::Mat &img2,
const VecVector2d &px_ref,
const vector<double> depth_ref,
Sophus::SE3 &T21
) {
// parameters
int pyramids = 4;
double pyramid_scale = 0.5;
double scales[] = {1.0, 0.5, 0.25, 0.125};
// create pyramids
vector<cv::Mat> pyr1, pyr2; // image pyramids
// TODO START YOUR CODE HERE
int width = img1.cols, height = img1.rows;
for (int i = 0; i < pyramids; i++) {
cv::Mat img1_temp, img2_temp;
resize(img1, img1_temp, cv::Size(width*scales[i], height*scales[i]));
resize(img2, img2_temp, cv::Size(width*scales[i], height*scales[i]));
pyr1.push_back(img1_temp);
pyr2.push_back(img2_temp);
cout << "image pyramids " << i <<" size: "<< img1_temp.cols << "X" << img1_temp.rows << endl;
}
// END YOUR CODE HERE
double fxG = fx, fyG = fy, cxG = cx, cyG = cy; // backup the old values
for (int level = pyramids - 1; level >= 0; level--) {
VecVector2d px_ref_pyr; // set the keypoints in this pyramid level
for (auto &px: px_ref) {
px_ref_pyr.push_back(scales[level] * px);
}
// TODO START YOUR CODE HERE
// scale fx, fy, cx, cy in different pyramid levels
fx = fxG*scales[level];
fy = fyG*scales[level];
cx = cxG*scales[level];
cy = cyG*scales[level];
// END YOUR CODE HERE
DirectPoseEstimationSingleLayer(pyr1[level], pyr2[level], px_ref_pyr, depth_ref, T21);
}
}
结果,
1th: T21 =
0.999992 0.00242692 -0.00328242 0.0345526
-0.00244611 0.99998 -0.00585421 0.00548916
0.00326815 0.0058622 0.999977 0.414297
0 0 0 1
2th: T21 =
0.999924 0.0110781 -0.00545024 0.0111684
-0.0111572 0.99983 -0.0147038 0.00171999
0.00528642 0.0147635 0.999877 0.715968
0 0 0 1
3th: T21 =
0.999696 0.0230745 -0.00868885 0.036758
-0.0232853 0.999416 -0.0250065 -0.00140524
0.00810677 0.0252012 0.99965 1.00699
0 0 0 1
4th: T21 =
0.999336 0.0353982 -0.00866001 0.0208662
-0.0356897 0.998707 -0.0362139 -0.016693
0.0073669 0.0364989 0.999307 1.22013
0 0 0 1
5th: T21 =
0.998884 0.0459784 -0.0107651 0.086995
-0.0464276 0.997859 -0.0460579 -0.034138
0.00862437 0.0465063 0.998881 1.31474
0 0 0 1
2.3 延伸讨论
现在你已经实现了金字塔上的 Gauss-Newton 直接法。你可以调整实验当中的一些参数,例如图像点 数、每个点周围小块的大小等等。请思考下面问题:
- 直接法是否可以类似光流,提出 inverse, compositional 的概念?它们有意义吗?
- 请思考上面算法哪些地方可以缓存或加速?
- 在上述过程中,我们实际假设了哪两个 patch 不变?
- 为何可以随机取点?而不用取角点或线上的点?那些不是角点的地方,投影算对了吗?
- 请总结直接法相对于特征点法的异同与优缺点。
三、使用光流计算视差
请注意本题为附加题。
在上一题中我们已经实现了金字塔 LK 光流。光流有很多用途,它给出了两个图像中点的对应关系,所 以我们可以用光流进行位姿估计,或者计算双目的视差。回忆第四节课的习题中,我们介绍了双目可以通过视差图得出点云,但那时直接给出了视差图,而没有进行视差图的计算。现在,给定图像 left.png,right.png, 请你使用上题的结果,计算 left.png 中的 GFTT 点在 right.png 中的(水平)视差,然后与 disparity.png 进行比较。这样的结果是一个稀疏角点组成的点云。请计算每个角点的水平视差,然后对比视差图比较结果。
本程序不提供代码框架,请你根据之前习题完成此内容。
代码:
int main(int argc, char **argv) {
// images, note they are CV_8UC1, not CV_8UC3
Mat img1 = imread(left_file, 0);
Mat img2 = imread(right_file, 0);
Mat disparity_gt = imread(disparity_file, 0);
// key points, using GFTT here.
vector<KeyPoint> kp1;
Ptr<GFTTDetector> detector = GFTTDetector::create(500, 0.01, 20); // maximum 500 keypoints
detector->detect(img1, kp1);
// now lets track these key points in the second image
vector<KeyPoint> kp2_multi;
vector<bool> success_multi;
// OpticalFlowMultiLevel(img1, img2, kp1, kp2_multi, success_multi);
OpticalFlowMultiLevel(img1, img2, kp1, kp2_multi, success_multi, true);
// plot the differences of those functions
int width = img1.cols, height = img1.rows;
Mat disparity_cal = Mat::zeros(height, width, CV_8UC1);
double error = 0;
int disp_count = 0;
for (int i = 0; i < kp2_multi.size(); i++) {
if (success_multi[i]) {
int u1 = kp1[i].pt.x, v1 = kp1[i].pt.y;
int u2 = kp2_multi[i].pt.x, v2 = kp2_multi[i].pt.y;
int disp = sqrt((v1-v2)*(v1-v2) + (u1-u2)*(u1-u2));
// cout << disp << endl;
disparity_cal.at<uchar>(v1, u1) = disp;
error += abs(disp - disparity_gt.at<uchar>(v1, u1));
disp_count++;
}
}
error /= disp_count;
cout << "error: " << error << endl;
cv::imshow("disparity_cal", disparity_cal);
cv::imshow("disparity_gt", disparity_gt);
cv::waitKey(0);
return 0;
}
结果: 最后的平均误差为 error:11.0292
kieranych@kieranych-ThinkPad-Edge-E431:~/vslam/hw6/code/LK_disparity/build$ ./optical_flow_disparity
image pyramids 0 size: 1241X376
image pyramids 1 size: 620X188
image pyramids 2 size: 310X94
image pyramids 3 size: 155X47
keypoint pyramids 3 | pyr_kp2_last size: 0
keypoint pyramids 3 | pyr_kp2_curr size: 368
keypoint pyramids 2 | pyr_kp2_last size: 368
keypoint pyramids 2 | pyr_kp2_curr size: 368
keypoint pyramids 1 | pyr_kp2_last size: 368
keypoint pyramids 1 | pyr_kp2_curr size: 368
keypoint pyramids 0 | pyr_kp2_last size: 368
keypoint pyramids 0 | pyr_kp2_curr size: 368
error:11.0292
评论区