1. 鱼眼相机

鱼眼相机镜头是由十几个不同的透镜组合而成,在成像的过程中,入射光线经过不同程度的折射,投影到尺寸有限的成像平面上,使得鱼眼镜头拥有更大的视野范围。下图为鱼眼相机的组成结构:

与针孔相机原理不同,鱼眼镜头采用非相似成像,在成像过程中引入畸变,通过对直径空间的压缩,突破成像视角的局限,从而达到广角成像。

鱼眼相机是一种焦距小于等于16mm,且视角接近或者等于180°的极端广角镜头,但是正是因为他极端的短焦和广角,导致它因为光学原理而产生的畸变非常剧烈,所以针孔模型并不能很好的描述鱼眼相机,所以需要一种新的相机模型来对鱼眼相机进行近似模拟。

2. 相机畸变

鱼眼镜头无论如何它的边缘线条都是要弯曲的,即使90度的鱼眼也是这样,这种畸变我们在很多广角镜头上都可以看到,而这就是明显的桶形畸变。同样的120度的鱼眼看起来弯曲的更加厉害一些了,而且被容纳进范围的景物更多;150度同样如此,而180度的鱼眼则可以把镜头周围180度范围内的所有物体都拍摄进去。众所周知,焦距越短,视角越大,因光学原理产生的变形也就越强烈。为了达到180度的超大视角,鱼眼镜头不得不允许这种变形(桶形畸变)的合理存在。

针对原始图像进行畸变校正后,带有冗余边界,需要做进一步截取。如下图:

3. KannalaBrandt8模型

KB模型能够很好的适用于普通,广角以及鱼眼镜头。KB模型假设图像光心到投影点的距离和角度的多项式存在比例关系,角度的定义是点所在的投影光纤和主轴之间的夹角。


3.1. 投影过程

其中

3.2. 反投影过程


4. KannalaBrandt8算法在ORB-SLAM3的实现

4.1.投影

/*** @brief 投影* @param 3D点* @return 像素坐标* 注意:ORBSLAM3为投影重载了许多方法以接受各种不同的数据类型,在此就不一一列举了* 它们只是进行了数据类型之间的转换,然后统一以本方式实现,不再赘述**/
cv::Point2f KannalaBrandt8::project(const cv::Point3f &p3D)
{// r^2 = x^2 + y^2const float x2_plus_y2 = p3D.x * p3D.x + p3D.y * p3D.y;// θ = atan2(r,z) const float theta = atan2f(sqrtf(x2_plus_y2), p3D.z);const float psi = atan2f(p3D.y, p3D.x);// 计算θ的3,5,7,9次方// 计算2次方是为了方便计算3,5,7,9次 相当于中间变量const float theta2 = theta * theta;const float theta3 = theta * theta2;const float theta5 = theta3 * theta2;const float theta7 = theta5 * theta2;const float theta9 = theta7 * theta2;// mvParameters是存放相机参数和畸变系数的数组// [4] [5] [6] [7] 分别代表k1 k2 k3 k4// 是不是感觉很熟悉 其实KB模型也常被用于针孔的畸变模型// 计算获得d(θ)const float r = theta + mvParameters[4] * theta3 + mvParameters[5] * theta5 + mvParameters[6] * theta7 + mvParameters[7] * theta9;// 注意:注释的r和代码的r不是一个东西 代码r = 注释d(θ) 注释r = 代码x2_plus_y2 // [0] [1] [2] [3] 分别代表 fx fy cx cy// 利用公式 u = (fx * d(θ) * xc) / r //           v = (fy * d(θ) * yc) / r// cos(psi) = xc/r  sin(psi) = yc/r  return cv::Point2f(mvParameters[0] * r * cos(psi) + mvParameters[2],mvParameters[1] * r * sin(psi) + mvParameters[3]);
}

4.2. 反投影

/*** @brief 反投影过程* @param 像素坐标* @return 归一化坐标**/
cv::Point3f KannalaBrandt8::unproject(const cv::Point2f &p2D)
{//Use Newton method to solve for theta with good precision (err ~ e-6)// 使用Newton法来求解θ,获得了很好的效果// 获取归一化的x,y坐标// x = (u - cx) / fx// y = (v - cy) / fycv::Point2f pw((p2D.x - mvParameters[2]) / mvParameters[0], (p2D.y - mvParameters[3]) / mvParameters[1]);  // xd   yd// 设置尺度为1float scale = 1.f;// xd = θd/r * xc   yd = θd/r * yc// xd^2 + yd^2 = (θd^2 / r^2) * (xc^2 + yc^2)// xc^2 + yc^2 = r^2// θ = (xd^2 + yd^2)^(1/2)float theta_d = sqrtf(pw.x * pw.x + pw.y * pw.y);  // sin(psi) = yc / r//确保θd在[-π,π]的范围内 theta_d = fminf(fmaxf(-CV_PI / 2.f, theta_d), CV_PI / 2.f);  // 不能超过180度// 已知θd 求解 θif (theta_d > 1e-8){//Compensate distortion iterativelyfloat theta = theta_d;  // θ的初始值定为了θd// 开始迭代for (int j = 0; j < 10; j++){float theta2 = theta * theta, theta4 = theta2 * theta2,theta6 = theta4 * theta2,theta8 = theta4 * theta4;float k0_theta2 = mvParameters[4] * theta2,k1_theta4 = mvParameters[5] * theta4;float k2_theta6 = mvParameters[6] * theta6,k3_theta8 = mvParameters[7] * theta8;// f(θ) = θ + k1 * θ^3 + k2 * θ^5 + k3 * θ^7 + k4 * θ^9// e(θ) = f(θ) - θd// 直接求解θ很难 所以通过求导优化的方法// 目标是优化获得e(θ) = 0对应的θ// e(θ)' = 1 + 3 * k1 * θ^2 + 5 * k2 * θ^4 + 7 * k3 * θ^6 + 9 * k4 * θ^8// δ(θ) = e(θ) / e(θ)' 修正量float theta_fix = (theta * (1 + k0_theta2 + k1_theta4 + k2_theta6 + k3_theta8) - theta_d) /(1 + 3 * k0_theta2 + 5 * k1_theta4 + 7 * k2_theta6 + 9 * k3_theta8);// 进行修正theta = theta - theta_fix;// 如果更新量变得很小,表示接近最终值if (fabsf(theta_fix) < precision) break;}//scale = theta - theta_d;// 求得tan(θ) / θdscale = std::tan(theta) / theta_d;}// 获取归一化坐标return cv::Point3f(pw.x * scale, pw.y * scale, 1.f);
}

4.3. 求解雅各比矩阵

/*** @breif 求解像素坐标关于三维点的雅各比矩阵* @param p3D 三维点* @return 雅各比矩阵[一个两行三列的矩阵] **/cv::Mat KannalaBrandt8::projectJac(const cv::Point3f &p3D)
{float x2 = p3D.x * p3D.x, y2 = p3D.y * p3D.y, z2 = p3D.z * p3D.z;float r2 = x2 + y2;float r = sqrt(r2);float r3 = r2 * r;float theta = atan2(r, p3D.z);float theta2 = theta * theta, theta3 = theta2 * theta;float theta4 = theta2 * theta2, theta5 = theta4 * theta;float theta6 = theta2 * theta4, theta7 = theta6 * theta;float theta8 = theta4 * theta4, theta9 = theta8 * theta;float f = theta + theta3 * mvParameters[4] + theta5 * mvParameters[5] + theta7 * mvParameters[6] +theta9 * mvParameters[7];float fd = 1 + 3 * mvParameters[4] * theta2 + 5 * mvParameters[5] * theta4 + 7 * mvParameters[6] * theta6 +9 * mvParameters[7] * theta8;// u = (fx * θd * x) / r + cx// v = (fy * θd * y) / r + cy// θd = θ + k1 * θ^3 + k2 * θ^5 + k3 * θ^7 + k4 * θ^9// θ = arctan(r,z)// r = (x^2 + y^2)^(1/2)cv::Mat Jac(2, 3, CV_32F);Jac.at<float>(0, 0) = mvParameters[0] * (fd * p3D.z * x2 / (r2 * (r2 + z2)) + f * y2 / r3);  // ∂u/∂xJac.at<float>(1, 0) =mvParameters[1] * (fd * p3D.z * p3D.y * p3D.x / (r2 * (r2 + z2)) - f * p3D.y * p3D.x / r3);  // ∂v/∂xJac.at<float>(0, 1) =mvParameters[0] * (fd * p3D.z * p3D.y * p3D.x / (r2 * (r2 + z2)) - f * p3D.y * p3D.x / r3);  // ∂u/∂yJac.at<float>(1, 1) = mvParameters[1] * (fd * p3D.z * y2 / (r2 * (r2 + z2)) + f * x2 / r3);  // ∂v/∂yJac.at<float>(0, 2) = -mvParameters[0] * fd * p3D.x / (r2 + z2);  // ∂u/∂zJac.at<float>(1, 2) = -mvParameters[1] * fd * p3D.y / (r2 + z2);  // ∂v/∂zstd::cout << "CV JAC: " << Jac << std::endl;return Jac.clone();
}

参考文献

ORBSLAM3(六) Kannala_Brandt鱼眼相机模型_Y.Q.Shi的博客-CSDN博客_鱼眼相机slam

一文搞懂鱼眼相机模型

KannalaBrandt8鱼眼相机模型相关推荐

  1. 【鱼眼相机模型】鱼眼相机投影模型理解

    一.从普通镜头到鱼眼镜头 如图1所示,普通镜头下的光线依据针孔相机模型进行成像(该部分可参考相机投影关系).但该模型存在一个缺陷:相机视野范围越大,所需的成像平面也越大,当相机视野范围要求在180°时 ...

  2. 一文尽览 | 计算机视觉中的鱼眼相机模型及环视感知任务汇总!

    点击下方卡片,关注"自动驾驶之心"公众号 ADAS巨卷干货,即可获取 点击进入→自动驾驶之心技术交流群 后台回复[ECCV2022]获取ECCV2022所有自动驾驶方向论文! 论文 ...

  3. Opencv中普通相机模型与鱼眼相机模型的区别

    普通相机模型 无畸变时相机模型的状态: 有畸变时的状态: 简单来讲就是获得地图点在归一化相机平面上的坐标[x',y']之后,进行加畸变操作,k1,k2,k3,k4,k5,k6都是径向畸变参数, 而p1 ...

  4. OpenCV中的鱼眼相机模型详解

    针孔相机.鱼眼相机模型推导: 一.针孔相机模型 空间的三维物体要成像到相机的 CMOS/CCD 上面,形成了图像.图像上的每个点对应空间上的一个点. 将世界坐标系上的一点 (x,y,z)映射到CMOS ...

  5. OpenCV——将针孔相机模型图片转换成鱼眼相机模型图片

    一 理论基础 关于针孔相机模型,参考博客: 关于鱼眼相机模型,参考参考文献[1][2]. 这里只需要知道我们这里使用的鱼眼相机模型是等距投影的鱼眼相机模型,即r=fθ(1),而针孔相机模型是透视投影, ...

  6. 针孔相机、鱼眼相机模型推导

    针孔相机.鱼眼相机模型 一.针孔相机模型 空间的三维物体要成像到相机的 CMOS/CCD 上面,形成了图像.图像上的每个点对应空间上的一个点. 将世界坐标系上的一点 (x,y,z)映射到CMOS/CC ...

  7. 视觉SLAM之鱼眼相机模型

    最近研究了视觉SLAM中不同的鱼眼相机模型,其中包括: Scaramuzza的鱼眼相机模型 代表性的SLAM工作为MultiCo-SLAM,是一个以ORB-SLAM为基础的扩展的多鱼眼相机视觉SLAM ...

  8. ORBSLAM3(六) Kannala_Brandt鱼眼相机模型

    z ORBSLAM3中src_cameraModels_KannalaBrandt8.cpp中完成了对于KB模型的代码,下面我们介绍一下鱼眼相机以及KB模型. 鱼眼相机 鱼眼相机是一种焦距小于等于16 ...

  9. 鱼眼相机标定_鱼眼相机模型(二)

    前言 在介绍其他相机模型之前,可以先看一下kalibr支持标定的相机模型(kalibr可以标定的相机模型),这里的相机模型一共有4种,针孔相机模型,全景相机模型,Double sphere相机模型还有 ...

最新文章

  1. CentOS Git服务安装
  2. 【转】data和attr的用法与区别
  3. poj 1390(消除方块(blocks))
  4. ACID中C与CAP定理中C的区别
  5. CAD国家制图员技术标准(OSTA)
  6. 高精度地图的学习笔记
  7. 小蚂蚁学习数据结构(26)——题目——输出二叉树上值大于x的算法
  8. .net 中文语音朗读
  9. MySQL游标(cursor) 定义及使用
  10. webstorm 配置sass 编译
  11. (转)Extjs4 展示图片与图片的更新
  12. 关于vs编译的程序无法正常启动(0xc0150002)的问题
  13. 客户价值度和活跃度建模
  14. 内网服务器设置proxy权限联通外网
  15. SEM和SD的区别和联系,以及其计算方法
  16. MySQL 递归 sql语句 WITH表达式实现
  17. 微信重磅功能更新!加好友按人数收费,视频号付费订阅、微信版“知乎”来了...
  18. Python之浅谈exec函数
  19. 短视频美颜sdk为什么会爆火?
  20. 360搜索、UC浏览器等被3·15点名应用已下架;马斯克宣布通过NFT卖歌;美团App再发力社交,内测 “群聊”功能...

热门文章

  1. 未能从程序集“xxx, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null”中加载类型“yyy”。
  2. 神经肿瘤组学基础知识、工作流程及应用
  3. 51单片机基础之DS1302
  4. CEF中文教程(google chrome浏览器控件) -- CEF简介
  5. 学习linux能有什么用
  6. oracle bpm难点,Oracle Bpm 11g 审批性能优化
  7. 鸟哥的linux私房菜 第八章
  8. element-ui日期选择器设置禁止选择时间(禁止选择今天之前或包含今天)
  9. matplotlib之pyplot模块——饼图(pie():圆环图(donut)、二层圆环图、三层圆环图(旭日图))
  10. ResNet论文翻译——中英文对照+标注总结