• 手撕 视觉slam14讲 ch13 代码(6)正常跟踪模式 Track()


    上一篇 双目初始化完成过程中,跟踪状态FrontendStatus变成了TRACKING_GOOD,因此之后,将进入 正常跟踪的Track() 函数:

    Track函数的流程也很清晰:

    • 首先,用匀速模型给当前帧的pose设置一个初值,这里用上一帧位姿获得当前位姿估计的初始值
    • 然后,用光流法匹配前后两帧的特征点(前后两帧都只用左目图像),并返回光流法匹配到的点的数量,对应TrackLastFrame()函数
    • 然后,根据匹配的特征点来优化当前帧的位置,对应EstimateCurrentPose() 函数。
    • 之后,根据追踪到的内点来判断现在的追踪状态,内点数大于50为TRACKING_GOOD,小于50大于20为TRACKING_BAD,如果小于等于20,就是跟丢了。
    • 然后,判断当前要不要插入关键帧,对应 InsertKeyframe() 函数
    • 之后,更新当前帧和上一帧的位置差
    • 最后,把当前帧送到viewer_线程里面。
    1. //正常状态下的跟踪
    2. bool Frontend::Track(){
    3. // 用上一帧位姿获得当前位姿估计的初始值
    4. // 假设匀速运动,即每两帧之间的位姿变换差不多,
    5. // 以【上一帧位姿】乘以【上上帧与上一帧之间的相对运动】作为这次位姿的估计初值
    6. if (last_frame_)
    7. {
    8. current_frame_->SetPose(relative_motion_ * last_frame_->Pose());
    9. }
    10. //用光流法匹配上一帧与当前帧,并返回光流法匹配到的点的数量
    11. int num_track_last= TrackLastFrame();
    12. // 修正当前帧的位姿估计,并返回追踪成功点数量(在光流匹配成功基础上,更信任的点)
    13. tracking_inliers_=EstimateCurrentPose();
    14. // 改变状态,为下次的添加帧做准备
    15. // tracking good
    16. if (tracking_inliers_>num_features_tracking_)
    17. {
    18. status_=FrontendStatus::TRACKING_GOOD;
    19. }
    20. // tracking bad
    21. else if (tracking_inliers_>num_features_tracking_bad_)
    22. {
    23. status_=FrontendStatus::TRACKING_BAD;
    24. }else // lost
    25. {
    26. status_=FrontendStatus::LOST;
    27. }
    28. //将当前帧插入关键帧
    29. InsertKeyframe();
    30. //当前帧位姿 = 上一帧的位姿 左乘 当前帧与上一帧的相对变换
    31. //相对位姿变换 = 当前帧的位姿 * 上一帧位姿的逆
    32. relative_motion_=current_frame_->Pose() * last_frame_->Pose().inverse();
    33. if (viewer_)
    34. {
    35. viewer_->AddCurrentFrame(current_frame_);
    36. return true;
    37. }
    38. }

    接下来我们具体看一下函数实现:

    TrackLastFrame() 函数:

    用光流法匹配上一帧与当前帧,并返回光流法匹配到的点的数量,这和前面左右目光流追踪FindFeaturesInRight() 函数基本一样,不同的是这里是上一帧和当前帧的左目图像来进行光流追踪,流程如下:

    • 第一步:进行赋初值。如果当前特征点有在地图上有对应的点,那么根据特征点的3D位置和匀速模型算的一个初值POSE来反推像素位置。如果没有对应特征点,当前帧的特征点初值就是和上一帧一样。
    • 第二步:调用OpenCV中的LK光流法来追踪右目特征点的位置
    • 第三步:把匹配上的特征点 push_back 到当前帧的左目特征点里面去,没匹配上就放个空指针。
    • 最后统计一下匹配上的特征点数目。
    1. //用光流法匹配上一帧与当前帧,并返回光流法匹配到的点的数量
    2. int Frontend::TrackLastFrame(){
    3. // 赋初值
    4. std::vector kps_last, kps_current;
    5. for(auto &kp : last_frame_->features_left_){
    6. // 如果这个点有对应的路标点,则当前帧的光流法初值为路标点对当前帧位姿(初值)的投影
    7. if (kp->map_point_.lock())
    8. {
    9. auto mp = kp->map_point_.lock();//检查是否上锁
    10. // 将世界坐标系中的坐标 投影 到像素坐标系上
    11. auto px = camera_left_->world2pixel(mp->Pos(),current_frame_->Pose());
    12. //关键帧的上一个容器中推入匹配到的关键点
    13. kps_last.push_back(kp->position_.pt);
    14. //当前帧中推入对应的像素坐标系上的坐标
    15. kps_current.push_back(cv::Point2f(px[0],px[1]));
    16. }
    17. //没有上锁,直接推入对应的地图点
    18. else{
    19. kps_last.push_back(kp->position_.pt);
    20. kps_current.push_back(kp->position_.pt);
    21. }
    22. }
    23. // 光流追踪
    24. std::vector status;// 设置一个状态的容器
    25. Mat error; //设置一个error矩阵
    26. cv::calcOpticalFlowPyrLK(last_frame_->left_img_,
    27. last_frame_->left_img_, kps_last, kps_current,
    28. status, error,
    29. cv::Size(11, 11), 3,
    30. cv::TermCriteria(cv::TermCriteria::COUNT + cv::TermCriteria::EPS, 30, 0.01),
    31. cv::OPTFLOW_USE_INITIAL_FLOW); // 最后一个参数flag,使用初始估计,存储在nextPts中;如果未设置标志,则将prevPts复制到nextPts并将其视为初始估计
    32. //统计匹配上的特征点个数,并存储
    33. int num_good_pts = 0;
    34. for (size_t i = 0; i < status.size(); ++i)
    35. {
    36. //如果匹配到对应的流则个数加一;并指针继续向后指
    37. if (status[i])
    38. {
    39. cv::KeyPoint kp(kps_current[i],7); // 关键点代表的区域直径大小为7
    40. Feature::Ptr feature(new Feature(current_frame_,kp)); // 有一个关键点,就要有一个特征类
    41. feature->map_point_=last_frame_->features_left_[i]->map_point_;// 关键点对应的地图点就是上一帧的点对应的地图点
    42. current_frame_->features_left_.push_back(feature);// 填充当前帧的左图特征点容器
    43. num_good_pts++;// 匹配成功点计数
    44. }
    45. }
    46. // 匹配成功的点数量记录到日志,并返回
    47. LOG(INFO) << "Find " << num_good_pts << " in the last image.";
    48. return num_good_pts;
    49. }

     EstimateCurrentPose() 函数

    估计当前帧位姿;与backend.cpp中的Optimize中的g2o优化相似,区别在于此处无需优化,只是估计出来,新建一些信息,这里很大一部分内容都是源自于《视觉SLAM14讲》第二版中的 P191g2o的实现过程,参考我之前写的手撕ch7(2)中的g2o的实现流程,

    • 步骤一: 创建线性方程求解器,确定分解方法
    • 步骤二: 构造线性方程的矩阵块,并用上面定义的线性求解器初始化
    • 步骤三: 创建总求解器 solver,并从 GN, LM, DogLeg 中选一个,再用上述块求解器 BlockSolver 初始化
    • 步骤四: 创建稀疏优化器(SparseOptimizer)
    • 步骤五: 自定义图的顶点和边,并添加到 SparseOptimizer 优化器中
    • 步骤六: 设置优化参数,开始执行优化
    • 步骤七: 使用卡方检查来区分哪些特征点是内点,哪些特征点是外点,参考,小葡萄:[ORB-SLAM2]卡方分布(Chi-squared)外点(outlier)剔除 ,主要思路是首先定义误差(误差要归一化,也就是去量纲化),然后选择置信度,一般为95%,如果这个特征点的误差在区间内我们认为是内外,否则是外点。
    • 步骤八:迭代优化完成之后,我们把优化估计的POSE给当前帧,把是外点的特征点对应的地点图删除,最后返回内点个数。

    原文代码:

    1. int Frontend::EstimateCurrentPose(){
    2. // setup g2o(g2o过程) 图优化:单节点+多条一元边
    3. // 设定g2o
    4. typedef ::g2o::BlockSolver_6_3 BlockSolverType;//pose 是 6 ,mappoint是 3
    5. typedef g2o::LinearSolverDense LinearSolverType; //线性求解器类型
    6. // 块求解器BlockSolver
    7. auto solver = new g2o::OptimizationAlgorithmLevenberg (
    8. g2o::make_unique( g2o::make_unique())); // 选择梯度下降法
    9. g2o::SparseOptimizer optimizer; //稀疏求解
    10. optimizer.setAlgorithm(solver); //设置求解器
    11. // vertex(优化量 顶点)
    12. VertexPose *vertex_pose= new VertexPose();// camera vertex_pose
    13. vertex_pose->setId(0);// 定义节点编号
    14. vertex_pose->setEstimate(current_frame_->Pose());//设置初值
    15. optimizer.addVertex(vertex_pose);//把节点添加到图中
    16. // K
    17. Mat33 K = camera_left_->K();
    18. // edges(约束 边)(每对匹配点就是一个边)
    19. int index =1;
    20. std::vectoredges;
    21. std::vectorfeatures;
    22. //遍历每一对点
    23. for (size_t i = 0; i < current_frame_->features_left_.size(); ++i)
    24. {
    25. auto mp = current_frame_->features_left_[i]->map_point_.lock();
    26. if (mp)
    27. {
    28. features.push_back(current_frame_->features_left_[i]);
    29. EdgeProjectionPoseOnly *edge = new EdgeProjectionPoseOnly(mp->pos_,K);
    30. edge->setId(index);
    31. edge->setVertex(0,vertex_pose);// 设置连接的顶点
    32. edge->setMeasurement(toVec2(current_frame_->features_left_[i]->position_.pt));//传入观测值
    33. edge->setInformation(Eigen::Matrix2d::Identity());// 信息矩阵
    34. edge->setRobustKernel(new g2o::RobustKernelHuber); //鲁棒核函数
    35. edges.push_back(edge);
    36. optimizer.addEdge(edge);
    37. index++;
    38. }
    39. }
    40. // estimate the Pose the determine the outliers
    41. // 要思路是首先定义误差(误差要归一化,也就是去量纲化),然后选择置信度,一般为95%,如果这个特征点的误差在区间内我们认为是内外,否则是外点
    42. const double chi2_th = 5.991;
    43. int cnt_outlier = 0;
    44. for (int iteration = 0; iteration < 4; ++iteration) {
    45. vertex_pose->setEstimate(current_frame_->Pose());
    46. optimizer.initializeOptimization();// 设置优化初始值
    47. optimizer.optimize(10);// 设置优化次数
    48. cnt_outlier = 0;
    49. // count the outliers
    50. for (size_t i = 0; i < edges.size(); ++i) {
    51. auto e = edges[i];
    52. if (features[i]->is_outlier_) {
    53. e->computeError();
    54. }
    55. if (e->chi2() > chi2_th) {
    56. //设置等级 一般情况下g2o只处理level = 0的边,设置等级为1,下次循环g2o不再优化这个边
    57. features[i]->is_outlier_ = true;
    58. e->setLevel(1);
    59. cnt_outlier++;
    60. } else {
    61. features[i]->is_outlier_ = false;
    62. e->setLevel(0);
    63. };
    64. // 在第三次迭代之后,它会将所有边的鲁棒核函数设置为nullptr,以便在后续的迭代中不再考虑outlier
    65. if (iteration == 2) {
    66. e->setRobustKernel(nullptr);
    67. }
    68. }
    69. }
    70. LOG(INFO) << "Outlier/Inlier in pose estimating: " << cnt_outlier << "/"
    71. << features.size() - cnt_outlier;
    72. // Set pose and outlier
    73. current_frame_->SetPose(vertex_pose->estimate());
    74. LOG(INFO) << "Current Pose = \n" << current_frame_->Pose().matrix();
    75. for (auto &feat : features) {
    76. if (feat->is_outlier_) {
    77. feat->map_point_.reset();
    78. feat->is_outlier_ = false; // maybe we can still use it in future
    79. }
    80. }
    81. return features.size() - cnt_outlier;
    82. }

    其中我们关注其中:自定义的顶点和边

    顶点(Vertex)
    1. // 位姿顶点
    2. class VertexPose : public g2o::BaseVertex<6,SE3>{//优化量的参数模板
    3. public:
    4. EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
    5. // 重置,设定被优化变量的原始值
    6. virtual void setToOriginImpl() override
    7. {
    8. _estimate =SE3();
    9. }
    10. // 更新
    11. virtual void oplusImpl(const double * update) override
    12. {
    13. Vec6 update_eigen;
    14. update_eigen << update[0], update[1], update[2], update[3], update[4], update[5];
    15. _estimate= SE3::exp(update_eigen) * _estimate; // 左乘更新 SE3 - 旋转矩阵R
    16. }
    17. // 存盘、读盘
    18. virtual bool read(std::istream &in) override { return true; } //存盘
    19. virtual bool write(std::ostream &out) const override { return true; } //读盘
    20. };
    边(edge)
    1. // 仅估计位姿的一元边
    2. class EdgeProjectionPoseOnly : public g2o::BaseUnaryEdge<2,Vec2,VertexPose>{
    3. public:
    4. EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
    5. // 构造函数
    6. EdgeProjectionPoseOnly(const Vec3 &pos, const Mat33 &K ): _pos3d(pos), _K(K) {}
    7. // 误差计算函数
    8. virtual void computeError() override{
    9. const VertexPose *v = static_cast(_vertices[0]);
    10. SE3 T = v->estimate();
    11. Vec3 pos_pixel= _K * (T*_pos3d); //将3D世界坐标转为相机像素坐标
    12. pos_pixel /= pos_pixel[2];
    13. _error=_measurement-pos_pixel.head<2>();
    14. }
    15. virtual void linearizeOplus() override {
    16. const VertexPose *v = static_cast(_vertices[0]);
    17. SE3 T = v->estimate();
    18. Vec3 pos_cam = T * _pos3d; //相机坐标系下空间点的坐标=相机位姿 * 空间点的坐标
    19. double fx = _K(0, 0);
    20. double fy = _K(1, 1);
    21. double X = pos_cam[0];
    22. double Y = pos_cam[1];
    23. double Z = pos_cam[2];
    24. double Zinv = 1.0 / (Z + 1e-18);
    25. double Zinv2 = Zinv * Zinv;
    26. //2*6的雅克比矩阵
    27. _jacobianOplusXi << -fx * Zinv, 0, fx * X * Zinv2, fx * X * Y * Zinv2,
    28. -fx - fx * X * X * Zinv2, fx * Y * Zinv, 0, -fy * Zinv,
    29. fy * Y * Zinv2, fy + fy * Y * Y * Zinv2, -fy * X * Y * Zinv2,
    30. -fy * X * Zinv;
    31. }
    32. // 读操作
    33. virtual bool read(std::istream &in) override { return true; }
    34. // 写操作
    35. virtual bool write(std::ostream &out) const override { return true; }
    36. private:
    37. Vec3 _pos3d;
    38. Mat33 _K;
    39. };

    至此EstimateCurrentPose() 函数完成,返回的当前帧追踪到的特征点内点数量(tracking_inliers_),然后判断当前的跟踪状态,为下次的添加帧做准备.如果内点数大于50 ,就是 tracking good ,内点数小于50大于20, 就是tracking bad,如果小于20,就 tracking lost .

    更新完跟踪状态后,进入 InsertKeyframe() 函数判断要不要插入关键帧

    InsertKeyframe() 函数:

    • 首先,如果目前追踪到的内点数大于80个,说明两帧差异不大,则不需要插入关键帧,return false,如果小于80个就把当前帧设置为关键帧,对应 Frame::SetKeyFrame()函数
    • 之后,把当前帧插入到局部地图中去,对应Map::InsertKeyFrame() 函数。其中如果当前激活的关键帧大于 num_active_keyframes_ (默认是7),就删除掉老的或太近的关键帧,对应 Map::RemoveOldKeyframe() 函数。
    • 然后对当前帧提取新的GFTT特征点,对应DetectFeatures()函数。
    • 接着匹配右目特征点,对应FindFeaturesInRight()函数。
    • 然后三角化新特征点并加入到地图中去,对应TriangulateNewPoints() 函数。
    • 因为添加了新的关键帧,所以在后端里面 运行 Backend::UpdateMap() 更新一下局部地图,启动一次局部地图的BA优化。
    • 最后把显示线程中的地图点也更新一下,对应Viewer::UpdateMap()函数。
    1. bool Frontend::InsertKeyframe(){
    2. // 如果追踪到的点很多(说明两帧差异不大),则不需要插入关键帧
    3. if (tracking_inliers_>num_features_needed_for_keyframe_)
    4. {
    5. return false;
    6. }
    7. // 如果追踪到的点很少(说明两帧差异较大),判定该帧为关键帧
    8. // 当前帧为关键帧并分配关键帧id
    9. current_frame_->SetKeyFrame();
    10. // 地图中插入当前帧
    11. map_->InsertKeyFrame(current_frame_);
    12. LOG(INFO) << "Set frame " << current_frame_->id_ << " as keyframe "
    13. << current_frame_->keyframe_id_;
    14. // 将关键帧中特征点对应的地图点加入到观测容器中
    15. SetObservationsForKeyFrame();
    16. // 关键帧重新提取特征点
    17. DetectFeatures();
    18. // track in right image 在关键帧的右目图像中找与左目对应的特征点
    19. FindFeaturesInRight();
    20. // triangulate map points 三角化新的地图点
    21. TriangulateNewPoints();
    22. // update backend because we have a new keyframe更新地图,触发后端优化
    23. backend_->UpdateMap();
    24. // 可视化模块中更新视图
    25. if (viewer_)
    26. {
    27. viewer_->UpdateMap();
    28. }
    29. }
    其中三角化TriangulateNewPoints()函数 流程和 上一篇(5) 双目初始化 StereoInit()中的triangulation() 三角化函数基本一样:
    1. // triangulate map points 三角化新的地图点
    2. int Frontend::TriangulateNewPoints(){
    3. // 1.左右目位姿(pose)
    4. std::vectorposes{camera_left_->pose(),camera_right_->pose()};
    5. SE3 current_pose_Twc=current_frame_->Pose().inverse();
    6. int cnt_triangulated_pts = 0;
    7. for (size_t i = 0; i < current_frame_->features_left_.size(); ++i)
    8. {
    9. //expired()函数用于检查智能指针指向的对象是否为空 ,expired()==true 存储空指针
    10. if (current_frame_->features_left_[i]->map_point_.expired() && current_frame_->features_right_[i] !=nullptr)
    11. {
    12. // 左图的特征点未关联地图点且存在右图匹配点
    13. // 2.左右目匹配点(point)
    14. std::vectorpoints{
    15. camera_left_->pixel2camera(
    16. Vec2(current_frame_->features_left_[i]->position_.pt.x, current_frame_->features_left_[i]->position_.pt.y)),
    17. camera_right_->pixel2camera(
    18. Vec2(current_frame_->features_right_[i]->position_.pt.x,current_frame_->features_right_[i]->position_.pt.y))
    19. };
    20. // 3 .pworld
    21. Vec3 pworld = Vec3::Zero();
    22. // 三角化成功并且深度为正
    23. if (triangulation(poses,points,pworld) && pworld[2]>0)
    24. {
    25. //创建一个新地图,用于信息更新
    26. auto new_map_point = MapPoint::CreateNewMappoint();
    27. //三角化得到的坐标是左目相机系坐标,这里和初始化中的triangulation区分:
    28. // 这里计算出的pworld是相机系坐标,左乘Twc才是世界系坐标, 而初始化是第一帧,一般以第一帧为世界系,因此得到的pworld直接当世界系坐标使用
    29. pworld = current_pose_Twc * pworld;
    30. new_map_point->SetPos(pworld);
    31. //将观测到的特征点加入新地图
    32. new_map_point->AddObservation(current_frame_->features_left_[i]);
    33. new_map_point->AddObservation(current_frame_->features_right_[i]);
    34. //为特征类Feature对象填写地图点成员
    35. current_frame_->features_left_[i]->map_point_=new_map_point;
    36. current_frame_->features_right_[i]->map_point_=new_map_point;
    37. //对Map类对象来说,地图里面应当多了一个地图点,所以要将这个地图点加到地图中去
    38. map_->InsertMapPoint(new_map_point);
    39. cnt_triangulated_pts++;
    40. }
    41. }
    42. }
    43. LOG(INFO) << "new landmarks: " << cnt_triangulated_pts;
    44. return cnt_triangulated_pts;
    45. }

    在InsertKeyframe()函数走完后,最后我们会把当前帧位姿和上一帧的位姿的差给到relative_motion_变量(相对位姿变换 = 当前帧的位姿 * 上一帧位姿的逆),最后在显示线程中添加当前帧,对应Viewer::AddCurrentFrame( )函数

    至此,前端的完整流程就全部写完(除了重定位没写)

  • 相关阅读:
    SpringBoot——自定义自动配置与起步依赖
    mac上VMware fusion net模式无法正常使用的问题
    servlet页面以及控制台输出中文乱码
    JVM内容
    牛客 HJ30 字符串合并处理
    哪个问卷工具便于团队作业?
    Word控件Spire.Doc 【表单域】教程(五):如何在 C# 中更新 Ask 字段
    当添加一个键值对元素时,HashMap发生了什么?
    spring 用户通过交互界面登录成功事件源码分析
    小红书种草推广步骤是怎样的,小红书种草效果好吗?
  • 原文地址:https://blog.csdn.net/weixin_62952541/article/details/133888099