当前位置:   article > 正文

LVI-SAM 视觉部分 feature_tracker.h 代码解析

feature_tracker.h

现在开始LVI-SAM 视觉部分的代码阅读。

头文件、命名空间

  1. #pragma once // 只编译一次
  2. #include <cstdio>
  3. #include <iostream>
  4. #include <queue>
  5. #include <execinfo.h>
  6. #include <csignal>
  7. #include <opencv2/opencv.hpp>
  8. #include <eigen3/Eigen/Dense>
  9. #include "camera_models/CameraFactory.h"
  10. #include "camera_models/CataCamera.h"
  11. #include "camera_models/PinholeCamera.h"
  12. #include "parameters.h"
  13. #include "tic_toc.h"
  14. using namespace std;
  15. using namespace camodocal;
  16. using namespace Eigen;

这上面没啥好说的,老一套了,所以不多讲。

一些函数

  1. // 判断跟踪的特征点是否在图像边界内
  2. bool inBorder(const cv::Point2f &pt);
  3. // 去除无法跟踪的特征点
  4. void reduceVector(vector<cv::Point2f> &v, vector<uchar> status);
  5. void reduceVector(vector<int> &v, vector<uchar> status);
  6. class FeatureTracker
  7. {
  8. public:
  9. FeatureTracker();
  10. void readImage(const cv::Mat &_img,double _cur_time); // 对图像使用光流法进行特征点跟踪
  11. void setMask(); // 对特征点进行排序并去除密集点
  12. void addPoints(); // 添加新检测到的特征点n_pts,ID初始化-1,跟踪次数1
  13. bool updateID(unsigned int i); // 更新特征点id
  14. void readIntrinsicParameter(const string &calib_file); // 读取相机内参
  15. void showUndistortion(const string &name); // 显示去畸变矫正后的特征点
  16. void rejectWithF(); // 通过F矩阵去除outliers
  17. void undistortedPoints(); // 对特征点的图像坐标去畸变矫正,并计算每个角点的速度

一些在头文件里面定义的函数,具体实现的话,还是要在cpp文件中进行详细的阅读。这些函数没啥好讲的,作用功能都写在注释里面了,自行阅读。

一些变量

  1. cv::Mat mask; // 图像掩码 好像也叫掩膜
  2. cv::Mat fisheye_mask; // 鱼眼相机mask,用来去除边缘噪点
  3. // prev_img是上一次发布的帧的图像数据
  4. // cur_img是光流跟踪的前一帧的图像数据
  5. // forw_img是光流跟踪的后一帧的图像数据
  6. cv::Mat prev_img, cur_img, forw_img;
  7. vector<cv::Point2f> n_pts; // 每一帧中新提取的特征点
  8. vector<cv::Point2f> prev_pts, cur_pts, forw_pts; // 对应的图像特征点
  9. vector<cv::Point2f> prev_un_pts, cur_un_pts; // 归一化相机坐标系下的坐标
  10. vector<cv::Point2f> pts_velocity; // 当前帧相对前一帧特征点沿x,y方向的像素移动速度
  11. vector<int> ids; // 能够被跟踪到的特征点的id
  12. vector<int> track_cnt; // 当前帧forw_img中每个特征点被跟踪的时间次数
  13. map<int, cv::Point2f> cur_un_pts_map;
  14. map<int, cv::Point2f> prev_un_pts_map;
  15. camodocal::CameraPtr m_camera; // 相机模型
  16. double cur_time;
  17. double prev_time;
  18. static int n_id; // 用来作为特征点的id,每检测到一个新的特征点,就将n_id作为该特征点的id,然后n_id的值加1

上面是一些变量,每个变量都有自己的意义。在这里的话,就是forw表示当前,cur是forw的前一帧,prev是cur的前一帧,这三个的时间关系务必搞清楚。

  1. class DepthRegister
  2. {
  3. public:
  4. ros::NodeHandle n;
  5. // publisher for visualization
  6. ros::Publisher pub_depth_feature;
  7. ros::Publisher pub_depth_image;
  8. ros::Publisher pub_depth_cloud;
  9. tf::TransformListener listener;
  10. tf::StampedTransform transform;
  11. const int num_bins = 360;
  12. vector<vector<PointType>> pointsArray;
  13. DepthRegister(ros::NodeHandle n_in): // 构造函数
  14. n(n_in)
  15. {
  16. // messages for RVIZ visualization 发布出去的信息,用于RVIZ可视化用的
  17. pub_depth_feature = n.advertise<sensor_msgs::PointCloud2>(PROJECT_NAME + "/vins/depth/depth_feature", 5);
  18. pub_depth_image = n.advertise<sensor_msgs::Image> (PROJECT_NAME + "/vins/depth/depth_image", 5);
  19. pub_depth_cloud = n.advertise<sensor_msgs::PointCloud2>(PROJECT_NAME + "/vins/depth/depth_cloud", 5);
  20. pointsArray.resize(num_bins);
  21. for (int i = 0; i < num_bins; ++i)
  22. pointsArray[i].resize(num_bins);
  23. }
  24. // 核心!
  25. sensor_msgs::ChannelFloat32 get_depth(const ros::Time& stamp_cur, const cv::Mat& imageCur,
  26. const pcl::PointCloud<PointType>::Ptr& depthCloud,
  27. const camodocal::CameraPtr& camera_model ,
  28. const vector<geometry_msgs::Point32>& features_2d)
  29. {
  30. // 0.1 initialize depth for return
  31. // 初始化需要返回的深度信息
  32. sensor_msgs::ChannelFloat32 depth_of_point;
  33. depth_of_point.name = "depth";
  34. depth_of_point.values.resize(features_2d.size(), -1);
  35. // 0.2 check if depthCloud available
  36. // 检查点云图是否可用
  37. if (depthCloud->size() == 0)
  38. return depth_of_point;
  39. // 0.3 look up transform at current image time
  40. // 在当前图像时间查找tf变换
  41. try{
  42. listener.waitForTransform("vins_world", "vins_body_ros", stamp_cur, ros::Duration(0.01));
  43. listener.lookupTransform("vins_world", "vins_body_ros", stamp_cur, transform);
  44. }
  45. catch (tf::TransformException ex)
  46. {
  47. ROS_ERROR("image no tf");
  48. return depth_of_point;
  49. }
  50. double xCur, yCur, zCur, rollCur, pitchCur, yawCur;
  51. xCur = transform.getOrigin().x();
  52. yCur = transform.getOrigin().y();
  53. zCur = transform.getOrigin().z();
  54. tf::Matrix3x3 m(transform.getRotation());
  55. m.getRPY(rollCur, pitchCur, yawCur);
  56. Eigen::Affine3f transNow = pcl::getTransformation(xCur, yCur, zCur, rollCur, pitchCur, yawCur);
  57. // 0.4 transform cloud from global frame to camera frame
  58. // 将点云图从世界坐标系转换到当前相机坐标系
  59. pcl::PointCloud<PointType>::Ptr depth_cloud_local(new pcl::PointCloud<PointType>());
  60. pcl::transformPointCloud(*depthCloud, *depth_cloud_local, transNow.inverse());
  61. // 0.5 project undistorted normalized (z) 2d features onto a unit sphere
  62. // 将未失真的归一化2d特征投影到单位球体上
  63. pcl::PointCloud<PointType>::Ptr features_3d_sphere(new pcl::PointCloud<PointType>());
  64. for (int i = 0; i < (int)features_2d.size(); ++i)
  65. {
  66. // normalize 2d feature to a unit sphere
  67. // 归一化2d特征到单位球体上
  68. Eigen::Vector3f feature_cur(features_2d[i].x, features_2d[i].y, features_2d[i].z); // z always equal to 1
  69. feature_cur.normalize();
  70. // convert to ROS standard
  71. // 转换为ROS的标准
  72. PointType p;
  73. p.x = feature_cur(2);
  74. p.y = -feature_cur(0);
  75. p.z = -feature_cur(1);
  76. p.intensity = -1; // intensity will be used to save depth
  77. // intensity会被用来保存深度信息
  78. features_3d_sphere->push_back(p);
  79. }
  80. // 3. project depth cloud on a range image, filter points satcked in the same region
  81. // 投影深度点云在距离图像上并过滤位于同一区域的点
  82. float bin_res = 180.0 / (float)num_bins; // currently only cover the space in front of lidar (-90 ~ 90) 只能覆盖lidar前面的-90~90区域
  83. cv::Mat rangeImage = cv::Mat(num_bins, num_bins, CV_32F, cv::Scalar::all(FLT_MAX));
  84. for (int i = 0; i < (int)depth_cloud_local->size(); ++i)
  85. {
  86. PointType p = depth_cloud_local->points[i];
  87. // filter points not in camera view
  88. // 过滤不在相机视野中的点
  89. if (p.x < 0 || abs(p.y / p.x) > 10 || abs(p.z / p.x) > 10)
  90. continue;
  91. // find row id in range image
  92. // 在图像的范围中找到行号
  93. float row_angle = atan2(p.z, sqrt(p.x * p.x + p.y * p.y)) * 180.0 / M_PI + 90.0; // degrees, bottom -> up, 0 -> 360
  94. int row_id = round(row_angle / bin_res);
  95. // find column id in range image
  96. // 在图像的范围中找到列号
  97. float col_angle = atan2(p.x, p.y) * 180.0 / M_PI; // degrees, left -> right, 0 -> 360
  98. int col_id = round(col_angle / bin_res);
  99. // id may be out of boundary
  100. // id可能超出约束条件
  101. if (row_id < 0 || row_id >= num_bins || col_id < 0 || col_id >= num_bins)
  102. continue;
  103. // only keep points that's closer
  104. // 只保留较近的点
  105. float dist = pointDistance(p); // 欧氏距离
  106. if (dist < rangeImage.at<float>(row_id, col_id))
  107. {
  108. rangeImage.at<float>(row_id, col_id) = dist;
  109. pointsArray[row_id][col_id] = p;
  110. }
  111. }
  112. // 4. extract downsampled depth cloud from range image
  113. // 从距离图像中提取下采样深度点云图
  114. pcl::PointCloud<PointType>::Ptr depth_cloud_local_filter2(new pcl::PointCloud<PointType>());
  115. for (int i = 0; i < num_bins; ++i)
  116. {
  117. for (int j = 0; j < num_bins; ++j)
  118. {
  119. if (rangeImage.at<float>(i, j) != FLT_MAX)
  120. depth_cloud_local_filter2->push_back(pointsArray[i][j]);
  121. }
  122. }
  123. *depth_cloud_local = *depth_cloud_local_filter2;
  124. publishCloud(&pub_depth_cloud, depth_cloud_local, stamp_cur, "vins_body_ros");
  125. // 5. project depth cloud onto a unit sphere
  126. // 将深度点云图投影到单位球体上
  127. pcl::PointCloud<PointType>::Ptr depth_cloud_unit_sphere(new pcl::PointCloud<PointType>());
  128. for (int i = 0; i < (int)depth_cloud_local->size(); ++i)
  129. {
  130. PointType p = depth_cloud_local->points[i];
  131. float range = pointDistance(p);
  132. p.x /= range;
  133. p.y /= range;
  134. p.z /= range;
  135. p.intensity = range; // 对于这里的深度,感觉就是距离的意思,当然理解成深度也是可以的
  136. depth_cloud_unit_sphere->push_back(p);
  137. }
  138. if (depth_cloud_unit_sphere->size() < 10)
  139. return depth_of_point;
  140. // 6. create a kd-tree using the spherical depth cloud
  141. // 使用球形深度点云创建kd树
  142. pcl::KdTreeFLANN<PointType>::Ptr kdtree(new pcl::KdTreeFLANN<PointType>());
  143. kdtree->setInputCloud(depth_cloud_unit_sphere);
  144. // 7. find the feature depth using kd-tree
  145. // 使用kd-tree找到特征深度,并返回结果
  146. vector<int> pointSearchInd;
  147. vector<float> pointSearchSqDis;
  148. float dist_sq_threshold = pow(sin(bin_res / 180.0 * M_PI) * 5.0, 2);
  149. for (int i = 0; i < (int)features_3d_sphere->size(); ++i)
  150. {
  151. kdtree->nearestKSearch(features_3d_sphere->points[i], 3, pointSearchInd, pointSearchSqDis);
  152. if (pointSearchInd.size() == 3 && pointSearchSqDis[2] < dist_sq_threshold)
  153. {
  154. float r1 = depth_cloud_unit_sphere->points[pointSearchInd[0]].intensity;
  155. Eigen::Vector3f A(depth_cloud_unit_sphere->points[pointSearchInd[0]].x * r1,
  156. depth_cloud_unit_sphere->points[pointSearchInd[0]].y * r1,
  157. depth_cloud_unit_sphere->points[pointSearchInd[0]].z * r1);
  158. float r2 = depth_cloud_unit_sphere->points[pointSearchInd[1]].intensity;
  159. Eigen::Vector3f B(depth_cloud_unit_sphere->points[pointSearchInd[1]].x * r2,
  160. depth_cloud_unit_sphere->points[pointSearchInd[1]].y * r2,
  161. depth_cloud_unit_sphere->points[pointSearchInd[1]].z * r2);
  162. float r3 = depth_cloud_unit_sphere->points[pointSearchInd[2]].intensity;
  163. Eigen::Vector3f C(depth_cloud_unit_sphere->points[pointSearchInd[2]].x * r3,
  164. depth_cloud_unit_sphere->points[pointSearchInd[2]].y * r3,
  165. depth_cloud_unit_sphere->points[pointSearchInd[2]].z * r3);
  166. // https://math.stackexchange.com/questions/100439/determine-where-a-vector-will-intersect-a-plane
  167. Eigen::Vector3f V(features_3d_sphere->points[i].x,
  168. features_3d_sphere->points[i].y,
  169. features_3d_sphere->points[i].z);
  170. Eigen::Vector3f N = (A - B).cross(B - C);
  171. float s = (N(0) * A(0) + N(1) * A(1) + N(2) * A(2))
  172. / (N(0) * V(0) + N(1) * V(1) + N(2) * V(2));
  173. float min_depth = min(r1, min(r2, r3));
  174. float max_depth = max(r1, max(r2, r3));
  175. if (max_depth - min_depth > 2 || s <= 0.5)
  176. {
  177. continue;
  178. }
  179. else if (s - max_depth > 0)
  180. {
  181. s = max_depth;
  182. }
  183. else if (s - min_depth < 0)
  184. {
  185. s = min_depth;
  186. }
  187. // convert feature into cartesian space if depth is available
  188. // 如果深度可用,则将特征转换为笛卡尔空间
  189. features_3d_sphere->points[i].x *= s;
  190. features_3d_sphere->points[i].y *= s;
  191. features_3d_sphere->points[i].z *= s;
  192. // the obtained depth here is for unit sphere, VINS estimator needs depth for normalized feature (by value z), (lidar x = camera z)
  193. // 这里获得的深度是针对单位球体的,VINS估计器需要归一化特征的深度(按z值)(激光雷达x = 相机z)
  194. features_3d_sphere->points[i].intensity = features_3d_sphere->points[i].x;
  195. }
  196. }
  197. // visualize features in cartesian 3d space (including the feature without depth (default 1))
  198. // 可视化笛卡尔3d空间中的特征(包括没有深度的特征(默认1))
  199. publishCloud(&pub_depth_feature, features_3d_sphere, stamp_cur, "vins_body_ros");
  200. // update depth value for return
  201. // 更新返回的深度值
  202. for (int i = 0; i < (int)features_3d_sphere->size(); ++i)
  203. {
  204. if (features_3d_sphere->points[i].intensity > 3.0)
  205. depth_of_point.values[i] = features_3d_sphere->points[i].intensity;
  206. }
  207. // visualization project points on image for visualization (it's slow!)
  208. // 可视化项目点在图像上进行可视化(很慢)
  209. if (pub_depth_image.getNumSubscribers() != 0)
  210. {
  211. vector<cv::Point2f> points_2d;
  212. vector<float> points_distance;
  213. for (int i = 0; i < (int)depth_cloud_local->size(); ++i)
  214. {
  215. // convert points from 3D to 2D
  216. // 将点从3D转换为2D
  217. Eigen::Vector3d p_3d(-depth_cloud_local->points[i].y,
  218. -depth_cloud_local->points[i].z,
  219. depth_cloud_local->points[i].x);
  220. Eigen::Vector2d p_2d;
  221. camera_model->spaceToPlane(p_3d, p_2d);
  222. points_2d.push_back(cv::Point2f(p_2d(0), p_2d(1)));
  223. points_distance.push_back(pointDistance(depth_cloud_local->points[i]));
  224. }
  225. cv::Mat showImage, circleImage;
  226. cv::cvtColor(imageCur, showImage, cv::COLOR_GRAY2RGB);
  227. circleImage = showImage.clone();
  228. for (int i = 0; i < (int)points_2d.size(); ++i)
  229. {
  230. float r, g, b;
  231. getColor(points_distance[i], 50.0, r, g, b);
  232. cv::circle(circleImage, points_2d[i], 0, cv::Scalar(r, g, b), 5);
  233. }
  234. cv::addWeighted(showImage, 1.0, circleImage, 0.7, 0, showImage); // blend camera image and circle image 混合相机图像和圆形图像
  235. cv_bridge::CvImage bridge;
  236. bridge.image = showImage;
  237. bridge.encoding = "rgb8";
  238. sensor_msgs::Image::Ptr imageShowPointer = bridge.toImageMsg();
  239. imageShowPointer->header.stamp = stamp_cur;
  240. pub_depth_image.publish(imageShowPointer);
  241. }
  242. return depth_of_point;
  243. }
  244. void getColor(float p, float np, float&r, float&g, float&b)
  245. {
  246. // 这里rgb表示三个通道的颜色,最后乘255,得到颜色的值
  247. float inc = 6.0 / np;
  248. float x = p * inc;
  249. r = 0.0f; g = 0.0f; b = 0.0f;
  250. if ((0 <= x && x <= 1) || (5 <= x && x <= 6)) r = 1.0f;
  251. else if (4 <= x && x <= 5) r = x - 4;
  252. else if (1 <= x && x <= 2) r = 1.0f - (x - 1);
  253. if (1 <= x && x <= 3) g = 1.0f;
  254. else if (0 <= x && x <= 1) g = x - 0;
  255. else if (3 <= x && x <= 4) g = 1.0f - (x - 3);
  256. if (3 <= x && x <= 5) b = 1.0f;
  257. else if (2 <= x && x <= 3) b = x - 2;
  258. else if (5 <= x && x <= 6) b = 1.0f - (x - 5);
  259. r *= 255.0;
  260. g *= 255.0;
  261. b *= 255.0;
  262. }
  263. };

这个的话就是DepthRegister类的具体内容。一开始定义了public的变量,用来rviz的可视化。然后下面是一个构造函数,用来可视化用的,这个没涉及到其他多余的操作,也不多讲。下面一个get_depth()的函数,这个非常重要,首先整理一下这个函数的流程。

get_depth()函数流程:

1、初始化需要返回的深度信息

2、检查点云图是否可用

3、在当前图像时间查找tf变换

4、将点云图从世界坐标系转换到当前相机坐标系

5、将未失真的归一化2d特征投影到单位球体上

6、投影深度点云在距离图像上并过滤位于同一区域的点

7、从距离图像中提取下采样深度点云图

8、将深度点云图投影到单位球体上

9、使用球形深度点云创建kd树

10、使用kd-tree找到特征深度,并放回结果

11、可视化笛卡尔三维空间中的特征

12、更新返回深度值

13、可视化项目点在图像上进行可视化

以上便是这个函数的流程,总共分了13步进行操作,猜测每一步代码比较简洁,因此就直接if,for这种直接上代码了,没有进行包装。一系列转换没啥好说的,然后转换矩阵要看懂,中间还有一步降采样的过程,也是为了减少不必要的计算了。然后创建kd树,这个数据结构的技巧,使得搜索更快。然后找到特征深度,里面r1、r2、r3这些公式的话,没太看懂。然后下面就是发布点云。这里的话,感觉没啥特别重要的,就是get_depth()这个要好好理解一下。

  1. void getColor(float p, float np, float&r, float&g, float&b)
  2. {
  3. // 这里rgb表示三个通道的颜色,最后乘255,得到颜色的值
  4. float inc = 6.0 / np;
  5. float x = p * inc;
  6. r = 0.0f; g = 0.0f; b = 0.0f;
  7. if ((0 <= x && x <= 1) || (5 <= x && x <= 6)) r = 1.0f;
  8. else if (4 <= x && x <= 5) r = x - 4;
  9. else if (1 <= x && x <= 2) r = 1.0f - (x - 1);
  10. if (1 <= x && x <= 3) g = 1.0f;
  11. else if (0 <= x && x <= 1) g = x - 0;
  12. else if (3 <= x && x <= 4) g = 1.0f - (x - 3);
  13. if (3 <= x && x <= 5) b = 1.0f;
  14. else if (2 <= x && x <= 3) b = x - 2;
  15. else if (5 <= x && x <= 6) b = 1.0f - (x - 5);
  16. r *= 255.0;
  17. g *= 255.0;
  18. b *= 255.0;
  19. }

上面这个函数的话就是获取颜色,rgb代表三个通道,然后根据if语句来进行rgb三通道的赋值,最后乘255即可得到了最终值。

本篇结,感觉自己没学到位,所以感觉好像没啥疑问的地方。。。

声明:本文内容由网友自发贡献,不代表【wpsshop博客】立场,版权归原作者所有,本站不承担相应法律责任。如您发现有侵权的内容,请联系我们。转载请注明出处:https://www.wpsshop.cn/w/盐析白兔/article/detail/116718
推荐阅读
相关标签
  

闽ICP备14008679号