VINS-Mono 代码详细解读——回环检测与重定位、四自由度位姿图优化

2023-05-16

本文主要介绍VINS的闭环检测重定位与位姿图优化部分,作为系列文章的最后一节。

回环检测的关键就是如何有效检测出相机曾经经过同一个地方,这样可以避免较大的累积误差,使得当前帧和之前的某一帧迅速建立约束,形成新的较小的累积误差。由于回环检测提供了当前数据与所有历史数据的关联,在跟踪算法丢失后,还可以利用重定位。

论文中主要分为两部分:回环检测与重定位4-DOF的位姿图优化

第一部分主要是为了通过回环检测找到当前帧和候选帧的联系,并通过简单的紧耦合重定位将局部滑动窗口移动与过去的位姿对齐。

第二部分是为了保证基于重定位结果对过去的所有位姿进行全局优化。

论文中内容为

0.4 重定位

vins的重定位模块主要包含回环检测,回环候选帧之间的特征匹配,紧耦合重定位三个部分

A、回环检测(只对关键帧)

1、采用DBoW2词袋位置识别方法进行回环检测。经过时间空间一致性检验后,DBoW2返回回环检测候选帧。

2、除了用于单目VIO的角点特征外,还添加了500个角点并使用BRIEF描述子,描述子用作视觉词袋在数据库里进行搜索。这些额外的角点能用来实现更好的回环检测。

3、VINS只保留所有用于特征检索的BRIEF描述子,丢弃原始图像以减小内存。

4、单目VIO可以观测到滚动和俯仰角,VINS并不需要依赖旋转不变性。

B、回环候选帧之间的特征匹配

1、检测到回环时,通过BRIEF描述子匹配找到对应关系。但是直接的描述子匹配会导致很多外点。

2、本文提出两步几何剔除法:

1)2D-2D:使用RANSAC进行F矩阵测试,

2)3D-2D:使用RANSAC进行PnP,基于已知的滑动窗特征点的3D位置,和回路闭合候选处图像的2D观测(像素坐标)。

当内点超过一定阈值时,我们将该候选帧视为正确的循环检测并执行重定位。

C、紧耦合重定位

1、重定位过程使单目VIO维持的当前滑动窗口过去的位姿图对齐

2、将所有回环帧的位姿作为常量,利用所有IMU测量值局部视觉测量和从回环中提取特征对应值,共同优化滑动窗口。

 0.5 全局位姿图优化

A、位姿图中添加关键帧

B、4自由度位姿图优化

C、位姿图管理


 在这里插入图片描述

相关代码都在pose_graph文件中,主要分为三个程序,分别为:

  • keyframe.cpp/.h 构建关键帧类、描述子计算、匹配关键帧与回环帧
  • pose_graph.cpp/.h 位姿图的建立与图优化、回环检测与闭环
  • pose_graph_node.cpp ROS 节点函数、回调函数、主线程

1、pose_graph_node.cpp

主要分为7个回调函数以及主线程process()函数。

7个回调函数:包括关键帧的位姿(keyframe_pose)、重定位位姿(relo_relative_pose)、相机到IMU的外参估计(extrinsic)、VIO里程计信息PQV(odometry)、关键帧中的3D点云(keyframe_point)、IMU传播值(imu_propagate)。
 

  1. ROS初始化,设置句柄

  2. 从launch文件读取参数和参数文件config中的参数

  3. 如果需要进行回环检测则读取词典和BRIEF描述子的模板文件,同时读取config中的其他参数、设置带回环的结果输出路径。

  4. 加载先前位姿图 loadPoseGraph()

  5. 订阅各个topic并执行各自回调函数

  6. 发布/pose_graph的topic

  7. 设置主线程 process() 和键盘控制线程 command()

int main(int argc, char **argv)
{
    // 1.ROS初始化,设置句柄
    ros::init(argc, argv, "pose_graph");
    ros::NodeHandle n("~");
    posegraph.registerPub(n);

    // 2.读取参数
    n.getParam("visualization_shift_x", VISUALIZATION_SHIFT_X);
    n.getParam("visualization_shift_y", VISUALIZATION_SHIFT_Y);
    n.getParam("skip_cnt", SKIP_CNT);
    n.getParam("skip_dis", SKIP_DIS);
    std::string config_file;
    n.getParam("config_file", config_file);
    cv::FileStorage fsSettings(config_file, cv::FileStorage::READ);
    if(!fsSettings.isOpened())
    {
        std::cerr << "ERROR: Wrong path to settings" << std::endl;
    }
    double camera_visual_size = fsSettings["visualize_camera_size"];
    cameraposevisual.setScale(camera_visual_size);
    cameraposevisual.setLineWidth(camera_visual_size / 10.0);
    LOOP_CLOSURE = fsSettings["loop_closure"];
    std::string IMAGE_TOPIC;
    int LOAD_PREVIOUS_POSE_GRAPH;

    //3.如果需要进行回环检测则读取词典和BRIEF描述子的模板文件,同时读取config中的其他参数、设置带回环的结果输出路径。
    if (LOOP_CLOSURE)
    {
        ROW = fsSettings["image_height"];
        COL = fsSettings["image_width"];

        // 3.1读取字典
        std::string pkg_path = ros::package::getPath("pose_graph");
        string vocabulary_file = pkg_path + "/../support_files/brief_k10L6.bin";
        cout << "vocabulary_file" << vocabulary_file << endl;
        posegraph.loadVocabulary(vocabulary_file);

        // 3.2读取BRIEF描述子的模板文件
        BRIEF_PATTERN_FILE = pkg_path + "/../support_files/brief_pattern.yml";
        cout << "BRIEF_PATTERN_FILE" << BRIEF_PATTERN_FILE << endl;
        m_camera = camodocal::CameraFactory::instance()->generateCameraFromYamlFile(config_file.c_str());

        fsSettings["image_topic"] >> IMAGE_TOPIC;        
        fsSettings["pose_graph_save_path"] >> POSE_GRAPH_SAVE_PATH;
        fsSettings["output_path"] >> VINS_RESULT_PATH;
        fsSettings["save_image"] >> DEBUG_IMAGE;
        VISUALIZE_IMU_FORWARD = fsSettings["visualize_imu_forward"];
        LOAD_PREVIOUS_POSE_GRAPH = fsSettings["load_previous_pose_graph"];
        FAST_RELOCALIZATION = fsSettings["fast_relocalization"];
        VINS_RESULT_PATH = VINS_RESULT_PATH + "/vins_result_loop.csv";
        std::ofstream fout(VINS_RESULT_PATH, std::ios::out);
        fout.close();
        fsSettings.release();

        // 3.3加载先前的位姿图
        if (LOAD_PREVIOUS_POSE_GRAPH)
        {
            printf("load pose graph\n");
            m_process.lock();
            posegraph.loadPoseGraph();
            m_process.unlock();
            printf("load pose graph finish\n");
            load_flag = 1;
        }
        else
        {
            printf("no previous pose graph\n");
            load_flag = 1;
        }
    }

    fsSettings.release();

    // 4.订阅话题topic并执行各自回调函数
    ros::Subscriber sub_imu_forward = n.subscribe("/vins_estimator/imu_propagate", 2000, imu_forward_callback);
    ros::Subscriber sub_vio = n.subscribe("/vins_estimator/odometry", 2000, vio_callback);
    ros::Subscriber sub_image = n.subscribe(IMAGE_TOPIC, 2000, image_callback);
    ros::Subscriber sub_pose = n.subscribe("/vins_estimator/keyframe_pose", 2000, pose_callback);
    ros::Subscriber sub_extrinsic = n.subscribe("/vins_estimator/extrinsic", 2000, extrinsic_callback);
    ros::Subscriber sub_point = n.subscribe("/vins_estimator/keyframe_point", 2000, point_callback);
    ros::Subscriber sub_relo_relative_pose = n.subscribe("/vins_estimator/relo_relative_pose", 2000, relo_relative_pose_callback);

    // 5.发布的话题topic
    pub_match_img = n.advertise<sensor_msgs::Image>("match_image", 1000);
    pub_camera_pose_visual = n.advertise<visualization_msgs::MarkerArray>("camera_pose_visual", 1000);
    pub_key_odometrys = n.advertise<visualization_msgs::Marker>("key_odometrys", 1000);
    pub_vio_path = n.advertise<nav_msgs::Path>("no_loop_path", 1000);
    pub_match_points = n.advertise<sensor_msgs::PointCloud>("match_points", 100);

    // 6. 创建两个线程,process 和 command
    std::thread measurement_process;
    std::thread keyboard_command_process;
    //pose graph主线程
    measurement_process = std::thread(process);
    //键盘操作的线程
    keyboard_command_process = std::thread(command);

    ros::spin();

    return 0;
}

2、process()函数

  1. 先判断是否需要回环检测

  2. 得到具有相同时间戳的pose_msg、image_msg、point_msg

  3. 构建pose_graph中用到的关键帧,然后每隔SKIP_CNT,将将距上一关键帧距离(平移向量的模)超过SKIP_DIS的图像创建为关键帧。其中,最核心的函数是KeyFrame类以及addKeyFrame()函数。

//主线程
void process()
{
    // 1.先判断是否需要回环检测
    if (!LOOP_CLOSURE)
        return;
    
    while (true)// 不断循环
    {
        // 三个参数图像、点云、VIO位姿
        sensor_msgs::ImageConstPtr image_msg = NULL;
        sensor_msgs::PointCloudConstPtr point_msg = NULL;
        nav_msgs::Odometry::ConstPtr pose_msg = NULL;

        // find out the messages with same time stamp
        // 2.得到具有相同时间戳的pose_msg、image_msg、point_msg
        m_buf.lock();
        if(!image_buf.empty() && !point_buf.empty() && !pose_buf.empty())// 首先三个都不为空
        {
            if (image_buf.front()->header.stamp.toSec() > pose_buf.front()->header.stamp.toSec())
            {
                pose_buf.pop();
                printf("throw pose at beginning\n");
            }
            else if (image_buf.front()->header.stamp.toSec() > point_buf.front()->header.stamp.toSec())
            {
                point_buf.pop();
                printf("throw point at beginning\n");
            }
            else if (image_buf.back()->header.stamp.toSec() >= pose_buf.front()->header.stamp.toSec() 
                && point_buf.back()->header.stamp.toSec() >= pose_buf.front()->header.stamp.toSec())
            {
                pose_msg = pose_buf.front();
                pose_buf.pop();
                while (!pose_buf.empty())
                    pose_buf.pop();

                while (image_buf.front()->header.stamp.toSec() < pose_msg->header.stamp.toSec())
                    image_buf.pop();
                image_msg = image_buf.front();
                image_buf.pop();

                while (point_buf.front()->header.stamp.toSec() < pose_msg->header.stamp.toSec())
                    point_buf.pop();
                point_msg = point_buf.front();
                point_buf.pop();
            }
        }
        m_buf.unlock();

        // 3.构建pose_graph中用到的关键帧,然后每隔SKIP_CNT,将将距上一关键帧距离(平移向量的模)超过SKIP_DIS的图像创建为关键帧。
        if (pose_msg != NULL)
        {
            //printf(" pose time %f \n", pose_msg->header.stamp.toSec());
            //printf(" point time %f \n", point_msg->header.stamp.toSec());
            //printf(" image time %f \n", image_msg->header.stamp.toSec());
            
            // skip first few
            // 3.1 剔除最开始的SKIP_FIRST_CNT帧,
            if (skip_first_cnt < SKIP_FIRST_CNT)
            {
                skip_first_cnt++;
                continue;
            }

            // 3.2每隔SKIP_CNT帧进行一次  SKIP_CNT=0
            if (skip_cnt < SKIP_CNT)
            {
                skip_cnt++;
                continue;
            }
            else
            {
                skip_cnt = 0;
            }
            // 3.3ROS图像转为Opencv类型
            cv_bridge::CvImageConstPtr ptr;
            if (image_msg->encoding == "8UC1")
            {
                sensor_msgs::Image img;
                img.header = image_msg->header;
                img.height = image_msg->height;
                img.width = image_msg->width;
                img.is_bigendian = image_msg->is_bigendian;
                img.step = image_msg->step;
                img.data = image_msg->data;
                img.encoding = "mono8";
                ptr = cv_bridge::toCvCopy(img, sensor_msgs::image_encodings::MONO8);
            }
            else
                ptr = cv_bridge::toCvCopy(image_msg, sensor_msgs::image_encodings::MONO8);
            
            cv::Mat image = ptr->image;
  
            // build keyframe
            Vector3d T = Vector3d(pose_msg->pose.pose.position.x,
                                  pose_msg->pose.pose.position.y,
                                  pose_msg->pose.pose.position.z);
            Matrix3d R = Quaterniond(pose_msg->pose.pose.orientation.w,
                                     pose_msg->pose.pose.orientation.x,
                                     pose_msg->pose.pose.orientation.y,
                                     pose_msg->pose.pose.orientation.z).toRotationMatrix();
            
            // 3.4 将距上一关键帧距离(平移向量的模)超过SKIP_DIS的图像创建为关键帧
            if((T - last_t).norm() > SKIP_DIS)
            {
                vector<cv::Point3f> point_3d; 
                vector<cv::Point2f> point_2d_uv; 
                vector<cv::Point2f> point_2d_normal;
                vector<double> point_id;

                for (unsigned int i = 0; i < point_msg->points.size(); i++)
                {
                    cv::Point3f p_3d;
                    p_3d.x = point_msg->points[i].x;
                    p_3d.y = point_msg->points[i].y;
                    p_3d.z = point_msg->points[i].z;
                    point_3d.push_back(p_3d);

                    cv::Point2f p_2d_uv, p_2d_normal;
                    double p_id;
                    p_2d_normal.x = point_msg->channels[i].values[0];
                    p_2d_normal.y = point_msg->channels[i].values[1];
                    p_2d_uv.x = point_msg->channels[i].values[2];
                    p_2d_uv.y = point_msg->channels[i].values[3];
                    p_id = point_msg->channels[i].values[4];
                    point_2d_normal.push_back(p_2d_normal);
                    point_2d_uv.push_back(p_2d_uv);
                    point_id.push_back(p_id);

                    //printf("u %f, v %f \n", p_2d_uv.x, p_2d_uv.y);
                }
                // 3.5 创建为关键帧类型并加入到posegraph中
                KeyFrame* keyframe = new KeyFrame(pose_msg->header.stamp.toSec(), frame_index, T, R, image,
                                   point_3d, point_2d_uv, point_2d_normal, point_id, sequence);   
                m_process.lock();

                start_flag = 1;
                //在posegraph中添加关键帧,flag_detect_loop=1回环检测
                posegraph.addKeyFrame(keyframe, 1);
                m_process.unlock();
                frame_index++;
                last_t = T;
            }
        }

        // 4.休眠5ms
        std::chrono::milliseconds dura(5);
        std::this_thread::sleep_for(dura);
    }
}

3、pose_graph.h

接下来将主要讲解两个函数:addKeyFrame()以及detectLoop()

4、addKeyFrame()添加关键帧,进行回环检测与闭环

  1. 建一个新的图像序列

  2. getVioPose()获取当前帧的位姿vio_P_cur、vio_R_cur并更新updateVioPose

  3. detectLoop()回环检测,返回回环候选帧的索引loop_index

  4. 计算当前帧与回环帧的相对位姿,纠正当前帧位姿w_P_cur、w_R_cur;回环得到的位姿和VIO位姿之间的偏移量shift_r、shift_t;如果存在多个图像序列,则将所有图像序列都合并到世界坐标系下

  5. 获取VIO当前帧的位姿P、R,根据偏移量得到实际位姿并更新updatePose当前帧的位姿P、R

  6. 发布path[sequence_cnt]

  7. 保存闭环轨迹到VINS_RESULT_PATH

void PoseGraph::addKeyFrame(KeyFrame* cur_kf, bool flag_detect_loop)
{
    //shift to base frame
    Vector3d vio_P_cur;
    Matrix3d vio_R_cur;

    // 1.建一个新的图像序列
    if (sequence_cnt != cur_kf->sequence)
    {
        sequence_cnt++;
        sequence_loop.push_back(0);
        w_t_vio = Eigen::Vector3d(0, 0, 0);
        w_r_vio = Eigen::Matrix3d::Identity();
        m_drift.lock();
        t_drift = Eigen::Vector3d(0, 0, 0);
        r_drift = Eigen::Matrix3d::Identity();
        m_drift.unlock();
    }
    
    // 2.getVioPose()获取当前帧的位姿vio_P_cur、vio_R_cur并更新updateVioPose
    cur_kf->getVioPose(vio_P_cur, vio_R_cur);
    vio_P_cur = w_r_vio * vio_P_cur + w_t_vio;
    vio_R_cur = w_r_vio * vio_R_cur;

    cur_kf->updateVioPose(vio_P_cur, vio_R_cur);
    cur_kf->index = global_index;
    global_index++;
	int loop_index = -1;

    if (flag_detect_loop)
    {
        TicToc tmp_t;
        // 3.detectLoop()回环检测,返回回环候选帧的索引loop_index
        loop_index = detectLoop(cur_kf, cur_kf->index);
    }
    else
    {
        addKeyFrameIntoVoc(cur_kf);
    }
    // 4.存在回环候选帧
	if (loop_index != -1)
	{
        //printf(" %d detect loop with %d \n", cur_kf->index, loop_index);
        
        // 4.1 获取回环候选帧 
        KeyFrame* old_kf = getKeyFrame(loop_index);

        // 当前帧与回环候选帧进行描述子匹配,如果成功则确定存在回环
        if (cur_kf->findConnection(old_kf))
        {
            //earliest_loop_index为最早的回环候选帧
            if (earliest_loop_index > loop_index || earliest_loop_index == -1)
                earliest_loop_index = loop_index;
            // 4.2 计算当前帧与回环帧的相对位姿,纠正当前帧位姿w_P_cur、w_R_cur
            Vector3d w_P_old, w_P_cur, vio_P_cur;
            Matrix3d w_R_old, w_R_cur, vio_R_cur;
            old_kf->getVioPose(w_P_old, w_R_old);
            cur_kf->getVioPose(vio_P_cur, vio_R_cur);

            //获取当前帧与回环帧的相对位姿relative_q、relative_t
            Vector3d relative_t;
            Quaterniond relative_q;
            relative_t = cur_kf->getLoopRelativeT();
            relative_q = (cur_kf->getLoopRelativeQ()).toRotationMatrix();

            //重新计算当前帧位姿w_P_cur、w_R_cur
            w_P_cur = w_R_old * relative_t + w_P_old;
            w_R_cur = w_R_old * relative_q;
            
            //回环得到的位姿和VIO位姿之间的偏移量shift_r、shift_t
            double shift_yaw;
            Matrix3d shift_r;
            Vector3d shift_t; 
            shift_yaw = Utility::R2ypr(w_R_cur).x() - Utility::R2ypr(vio_R_cur).x();
            shift_r = Utility::ypr2R(Vector3d(shift_yaw, 0, 0));
            shift_t = w_P_cur - w_R_cur * vio_R_cur.transpose() * vio_P_cur; 
            
            // shift vio pose of whole sequence to the world frame
            // 4.3如果存在多个图像序列,则将所有图像序列都合并到世界坐标系下
            if (old_kf->sequence != cur_kf->sequence && sequence_loop[cur_kf->sequence] == 0)
            {  
                w_r_vio = shift_r;
                w_t_vio = shift_t;
                vio_P_cur = w_r_vio * vio_P_cur + w_t_vio;
                vio_R_cur = w_r_vio *  vio_R_cur;
                cur_kf->updateVioPose(vio_P_cur, vio_R_cur);
                list<KeyFrame*>::iterator it = keyframelist.begin();
                for (; it != keyframelist.end(); it++)   
                {
                    if((*it)->sequence == cur_kf->sequence)
                    {
                        Vector3d vio_P_cur;
                        Matrix3d vio_R_cur;
                        (*it)->getVioPose(vio_P_cur, vio_R_cur);
                        vio_P_cur = w_r_vio * vio_P_cur + w_t_vio;
                        vio_R_cur = w_r_vio *  vio_R_cur;
                        (*it)->updateVioPose(vio_P_cur, vio_R_cur);
                    }
                }
                sequence_loop[cur_kf->sequence] = 1;
            }

            // 4.4 将当前帧放入优化队列中
            m_optimize_buf.lock();
            optimize_buf.push(cur_kf->index);
            m_optimize_buf.unlock();
        }
	}

    
	m_keyframelist.lock();
    Vector3d P;
    Matrix3d R;
 
    // 5.获取VIO当前帧的位姿P、R,根据偏移量得到实际位姿
    cur_kf->getVioPose(P, R);
    P = r_drift * P + t_drift;
    R = r_drift * R;
    // 更新当前帧的位姿P、R
    cur_kf->updatePose(P, R);

    // 6.发布path[sequence_cnt]
    Quaterniond Q{R};
    geometry_msgs::PoseStamped pose_stamped;
    pose_stamped.header.stamp = ros::Time(cur_kf->time_stamp);
    pose_stamped.header.frame_id = "world";
    pose_stamped.pose.position.x = P.x() + VISUALIZATION_SHIFT_X;
    pose_stamped.pose.position.y = P.y() + VISUALIZATION_SHIFT_Y;
    pose_stamped.pose.position.z = P.z();
    pose_stamped.pose.orientation.x = Q.x();
    pose_stamped.pose.orientation.y = Q.y();
    pose_stamped.pose.orientation.z = Q.z();
    pose_stamped.pose.orientation.w = Q.w();
    path[sequence_cnt].poses.push_back(pose_stamped);
    path[sequence_cnt].header = pose_stamped.header;

    // 7.保存闭环轨迹到VINS_RESULT_PATH
    if (SAVE_LOOP_PATH)
    {
        ofstream loop_path_file(VINS_RESULT_PATH, ios::app);
        loop_path_file.setf(ios::fixed, ios::floatfield);
        loop_path_file.precision(0);
        loop_path_file << cur_kf->time_stamp * 1e9 << ",";
        loop_path_file.precision(5);
        loop_path_file  << P.x() << ","
              << P.y() << ","
              << P.z() << ","
              << Q.w() << ","
              << Q.x() << ","
              << Q.y() << ","
              << Q.z() << ","
              << endl;
        loop_path_file.close();
    }

    // 8.draw local connection
    if (SHOW_S_EDGE)
    {
        list<KeyFrame*>::reverse_iterator rit = keyframelist.rbegin();
        for (int i = 0; i < 4; i++)
        {
            if (rit == keyframelist.rend())
                break;
            Vector3d conncected_P;
            Matrix3d connected_R;
            if((*rit)->sequence == cur_kf->sequence)
            {
                (*rit)->getPose(conncected_P, connected_R);
                posegraph_visualization->add_edge(P, conncected_P);
            }
            rit++;
        }
    }
    //当前帧与其回环帧连线
    if (SHOW_L_EDGE)
    {
        if (cur_kf->has_loop)
        {
            //printf("has loop \n");
            KeyFrame* connected_KF = getKeyFrame(cur_kf->loop_index);
            Vector3d connected_P,P0;
            Matrix3d connected_R,R0;
            connected_KF->getPose(connected_P, connected_R);
            //cur_kf->getVioPose(P0, R0);
            cur_kf->getPose(P0, R0);
            if(cur_kf->sequence > 0)
            {
                //printf("add loop into visual \n");
                posegraph_visualization->add_loopedge(P0, connected_P + Vector3d(VISUALIZATION_SHIFT_X, VISUALIZATION_SHIFT_Y, 0));
            }
            
        }
    }
    //posegraph_visualization->add_pose(P + Vector3d(VISUALIZATION_SHIFT_X, VISUALIZATION_SHIFT_Y, 0), Q);

	keyframelist.push_back(cur_kf);
    publish();
	m_keyframelist.unlock();
}

5、detectLoop()回环检测返回候选帧索引

  1. query()查询字典数据库,得到与每一帧的相似度评分ret
  2. add()添加当前关键帧到字典数据库中
  3. hconcat()通过相似度评分判断是否存在回环候选帧

  4. 对于索引值大于50的关键帧才考虑进行回环,即前50帧不回环,返回评分大于0.015的最早的关键帧索引min_index

//回环检测返回候选帧索引
int PoseGraph::detectLoop(KeyFrame* keyframe, int frame_index)
{
    // put image into image_pool; for visualization
    cv::Mat compressed_image;
    if (DEBUG_IMAGE)
    {
        int feature_num = keyframe->keypoints.size();
        cv::resize(keyframe->image, compressed_image, cv::Size(376, 240));
        putText(compressed_image, "feature_num:" + to_string(feature_num), cv::Point2f(10, 10), CV_FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(255));
        image_pool[frame_index] = compressed_image;
    }
    TicToc tmp_t;

    QueryResults ret;
    TicToc t_query;

    // 1.查询字典数据库,得到与每一帧的相似度评分ret
    db.query(keyframe->brief_descriptors, ret, 4, frame_index - 50);
    //printf("query time: %f", t_query.toc());
    //cout << "Searching for Image " << frame_index << ". " << ret << endl;

    // 2.添加当前关键帧到字典数据库中
    TicToc t_add;
    db.add(keyframe->brief_descriptors);
    //printf("add feature time: %f", t_add.toc());
    
    // ret[0] is the nearest neighbour's score. threshold change with neighour score
   // 3.通过相似度评分判断是否存在回环候选帧
    bool find_loop = false;
    cv::Mat loop_result;

    if (DEBUG_IMAGE)
    {
        loop_result = compressed_image.clone();
        if (ret.size() > 0)
            putText(loop_result, "neighbour score:" + to_string(ret[0].Score), cv::Point2f(10, 50), CV_FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(255));
    }

    // visual loop result 
    if (DEBUG_IMAGE)
    {
        for (unsigned int i = 0; i < ret.size(); i++)
        {
            int tmp_index = ret[i].Id;
            auto it = image_pool.find(tmp_index);
            cv::Mat tmp_image = (it->second).clone();
            putText(tmp_image, "index:  " + to_string(tmp_index) + "loop score:" + to_string(ret[i].Score), cv::Point2f(10, 50), CV_FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(255));
            cv::hconcat(loop_result, tmp_image, loop_result);
        }
    }

    //确保与相邻帧具有好的相似度评分
    if (ret.size() >= 1 &&ret[0].Score > 0.05)
        for (unsigned int i = 1; i < ret.size(); i++)
        {
            //if (ret[i].Score > ret[0].Score * 0.3)
            //评分大于0.015则认为是回环候选帧
            if (ret[i].Score > 0.015)
            {          
                find_loop = true;
                int tmp_index = ret[i].Id;
                if (DEBUG_IMAGE && 0)
                {
                    auto it = image_pool.find(tmp_index);
                    cv::Mat tmp_image = (it->second).clone();
                    putText(tmp_image, "loop score:" + to_string(ret[i].Score), cv::Point2f(10, 50), CV_FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(255));
                    cv::hconcat(loop_result, tmp_image, loop_result);
                }
            }

        }
/*
    if (DEBUG_IMAGE)
    {
        cv::imshow("loop_result", loop_result);
        cv::waitKey(20);
    }
*/
    // 4.对于索引值大于50的关键帧才考虑进行回环,即前50帧不回环
    //返回评分大于0.015的最早的关键帧索引min_index
    if (find_loop && frame_index > 50)
    {
        int min_index = -1;
        for (unsigned int i = 0; i < ret.size(); i++)
        {
            if (min_index == -1 || (ret[i].Id < min_index && ret[i].Score > 0.015))
                min_index = ret[i].Id;
        }
        return min_index;
    }
    else
        return -1;

}

6、optimize4DoF()位姿图优化

//四自由度位姿图优化
void PoseGraph::optimize4DoF()
{
    while(true)
    {
        int cur_index = -1;
        int first_looped_index = -1;

        //取出最新一个待优化帧作为当前帧
        m_optimize_buf.lock();
        while(!optimize_buf.empty())
        {
            cur_index = optimize_buf.front();
            first_looped_index = earliest_loop_index;
            optimize_buf.pop();
        }
        m_optimize_buf.unlock();

        if (cur_index != -1)
        {
            printf("optimize pose graph \n");
            TicToc tmp_t;

            m_keyframelist.lock();
            KeyFrame* cur_kf = getKeyFrame(cur_index);

            int max_length = cur_index + 1;

            // w^t_i   w^q_i
            double t_array[max_length][3];
            Quaterniond q_array[max_length];
            double euler_array[max_length][3];
            double sequence_array[max_length];

            ceres::Problem problem;
            ceres::Solver::Options options;
            options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
            //options.minimizer_progress_to_stdout = true;
            //options.max_solver_time_in_seconds = SOLVER_TIME * 3;
            options.max_num_iterations = 5;
            ceres::Solver::Summary summary;
            ceres::LossFunction *loss_function;
            loss_function = new ceres::HuberLoss(0.1);
            //loss_function = new ceres::CauchyLoss(1.0);
            ceres::LocalParameterization* angle_local_parameterization =
                AngleLocalParameterization::Create();

            list<KeyFrame*>::iterator it;

            int i = 0;
            for (it = keyframelist.begin(); it != keyframelist.end(); it++)
            {
                //找到第一个回环候选帧,
                //回环检测到帧以前的都略过
                if ((*it)->index < first_looped_index)
                    continue;
                (*it)->local_index = i;
                Quaterniond tmp_q;
                Matrix3d tmp_r;
                Vector3d tmp_t;
                (*it)->getVioPose(tmp_t, tmp_r);
                tmp_q = tmp_r;
                t_array[i][0] = tmp_t(0);
                t_array[i][1] = tmp_t(1);
                t_array[i][2] = tmp_t(2);
                q_array[i] = tmp_q;

                Vector3d euler_angle = Utility::R2ypr(tmp_q.toRotationMatrix());
                euler_array[i][0] = euler_angle.x();
                euler_array[i][1] = euler_angle.y();
                euler_array[i][2] = euler_angle.z();

                sequence_array[i] = (*it)->sequence;

                problem.AddParameterBlock(euler_array[i], 1, angle_local_parameterization);
                problem.AddParameterBlock(t_array[i], 3);

                //回环检测到的帧参数设为固定
                if ((*it)->index == first_looped_index || (*it)->sequence == 0)
                {   
                    problem.SetParameterBlockConstant(euler_array[i]);
                    problem.SetParameterBlockConstant(t_array[i]);
                }

                //add edge
                //对于每个i, 只计算它之前五个的位置和yaw残差
                for (int j = 1; j < 5; j++)
                {
                  if (i - j >= 0 && sequence_array[i] == sequence_array[i-j])
                  {
                    Vector3d euler_conncected = Utility::R2ypr(q_array[i-j].toRotationMatrix());
                    Vector3d relative_t(t_array[i][0] - t_array[i-j][0], t_array[i][1] - t_array[i-j][1], t_array[i][2] - t_array[i-j][2]);
                    relative_t = q_array[i-j].inverse() * relative_t;
                    double relative_yaw = euler_array[i][0] - euler_array[i-j][0];
                    ceres::CostFunction* cost_function = FourDOFError::Create( relative_t.x(), relative_t.y(), relative_t.z(),
                                                   relative_yaw, euler_conncected.y(), euler_conncected.z());
                    problem.AddResidualBlock(cost_function, NULL, euler_array[i-j], 
                                            t_array[i-j], 
                                            euler_array[i], 
                                            t_array[i]);
                  }
                }

                //add loop edge
                if((*it)->has_loop)// 如果检测到回环
                {
                     //必须回环检测的帧号大于或者等于当前帧的回环检测匹配帧号
                    assert((*it)->loop_index >= first_looped_index);
                    int connected_index = getKeyFrame((*it)->loop_index)->local_index;
                    Vector3d euler_conncected = Utility::R2ypr(q_array[connected_index].toRotationMatrix());
                    Vector3d relative_t;
                    relative_t = (*it)->getLoopRelativeT();
                    double relative_yaw = (*it)->getLoopRelativeYaw();
                    ceres::CostFunction* cost_function = FourDOFWeightError::Create( relative_t.x(), relative_t.y(), relative_t.z(),
                                                                               relative_yaw, euler_conncected.y(), euler_conncected.z());
                    problem.AddResidualBlock(cost_function, loss_function, euler_array[connected_index], 
                                                                  t_array[connected_index], 
                                                                  euler_array[i], 
                                                                  t_array[i]);
                    
                }
                
                if ((*it)->index == cur_index)
                    break;
                i++;
            }
            m_keyframelist.unlock();

            ceres::Solve(options, &problem, &summary);
            //std::cout << summary.BriefReport() << "\n";
            
            //printf("pose optimization time: %f \n", tmp_t.toc());
            /*
            for (int j = 0 ; j < i; j++)
            {
                printf("optimize i: %d p: %f, %f, %f\n", j, t_array[j][0], t_array[j][1], t_array[j][2] );
            }
            */

            m_keyframelist.lock();
            i = 0;
            //根据优化后的参数更新参与优化的关键帧的位姿
            for (it = keyframelist.begin(); it != keyframelist.end(); it++)
            {
                if ((*it)->index < first_looped_index)
                    continue;
                Quaterniond tmp_q;
                tmp_q = Utility::ypr2R(Vector3d(euler_array[i][0], euler_array[i][1], euler_array[i][2]));
                Vector3d tmp_t = Vector3d(t_array[i][0], t_array[i][1], t_array[i][2]);
                Matrix3d tmp_r = tmp_q.toRotationMatrix();
                (*it)-> updatePose(tmp_t, tmp_r);

                if ((*it)->index == cur_index)
                    break;
                i++;
            }
            //根据当前帧的drift,更新全部关键帧位姿
            Vector3d cur_t, vio_t;
            Matrix3d cur_r, vio_r;
            cur_kf->getPose(cur_t, cur_r);
            cur_kf->getVioPose(vio_t, vio_r);
            m_drift.lock();
            yaw_drift = Utility::R2ypr(cur_r).x() - Utility::R2ypr(vio_r).x();
            r_drift = Utility::ypr2R(Vector3d(yaw_drift, 0, 0));
            t_drift = cur_t - r_drift * vio_t;
            m_drift.unlock();
            //cout << "t_drift " << t_drift.transpose() << endl;
            //cout << "r_drift " << Utility::R2ypr(r_drift).transpose() << endl;
            //cout << "yaw drift " << yaw_drift << endl;

            it++;
            for (; it != keyframelist.end(); it++)
            {
                Vector3d P;
                Matrix3d R;
                (*it)->getVioPose(P, R);
                P = r_drift * P + t_drift;
                R = r_drift * R;
                (*it)->updatePose(P, R);
            }
            m_keyframelist.unlock();
            updatePath();
        }

        std::chrono::milliseconds dura(2000);
        std::this_thread::sleep_for(dura);
    }
}

7、keyframe.h

主要有两个类:BriefExtractor和KeyFrame

第一个类BriefExtractor:通过Brief模板文件,对图像的关键点计算Brief描述子

class BriefExtractor
{
public:
  virtual void operator()(const cv::Mat &im, vector<cv::KeyPoint> &keys, vector<BRIEF::bitset> &descriptors) const;
  BriefExtractor(const std::string &pattern_file);

  DVision::BRIEF m_brief;
};

第二个类KeyFrame:构建关键帧,通过BRIEF描述子匹配关键帧和回环候选帧

 

 

代码流程图的出处:VINS-Mono代码解读——回环检测与重定位 pose graph loop closing by Manii

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

VINS-Mono 代码详细解读——回环检测与重定位、四自由度位姿图优化 的相关文章

  • C语言学习笔记w2d4

    文章目录 流程控制二循环语句gotowhile练习 do whilefor breakcontinue 作业 流程控制二 循环语句 循环的开始条件 循环的控制条件 循环的结束条件 goto 无条件跳转 xff0c 跳转到指定位置执行 xff
  • C语言学习笔记w2d5

    文章目录 数组一维数组练习字符数组字符串输入与输出 练习 多维数组 作业 数组 一维数组 用一个变量来存储具有一定关系的数据 xff0c 的数据集合叫数组 其中存储的变量是数组元素 a span class token punctuatio
  • Linux基础与C高级w3d4:linux的文件管理(续)、了解shell编程

    管道 作用 xff1a 把一个命令的结果作为另一个命令的输入参数 符号 xff1a 用法 xff1a ls grep test 用户管理 切换用户 xff1a su 用户名 修改用户密码 xff1a sudo passwd 用户 注册用户
  • ARM:day4

    ARM 的接口技术 裸机编程 例 xff1a LED灯 根据电路图找到 LED 找到控制的管脚 GPX2 7根据芯片手册 找到需要配置的地址空间地址 和使能值写汇编代码 编译工具 arm gcc 安装方式 把 bin 添加到PATH bas
  • ARM:day5

    ARM 的接口技术 串口 UART 工作模式 全双工发送二进制 ASCII码 两个设备通过各自的定时器来接收数据 空闲时拉高电平 要开始发数据时起始位拉低 0 发数据 一般是 8 位带一位校验位 结束发送 拉高电平回到空闲状态 缺点 特点
  • Ubuntu上igraph的安装教程

    暑假终于到了 xff0c 距离上一篇博客应该有3个月的时间了 xff0c 没有学期末的忙忙碌碌 xff0c 接下来会陆陆续续地回顾自己学过的和将学的东西一并整理成博客 关于igraph 因为课程需要 xff0c 在信息资源管理的课程上曾学过
  • 还在按鼠标调试?键盘F1-F10取消Fn快速调试

    传统功能键 xff1a F1 F12媒体功能键 xff1a 音量 xff0c 亮度 xff0c 锁屏 xff0c 飞行模式等 多数电脑 xff0c 或者有些升级为win10的电脑 xff0c 传统功能键变为了媒体功能键 xff0c 开发人员
  • Jupyter Notebook+VSCode环境搭建及原理讲解

    版权所有 xff0c 转载注明原地址 时间 xff1a 2020年1月17日17 33 15 created by xff1a Hpbbs 使用JupyterNotebook编辑 文章目录 0x00 前言 Python命令行模式的单一与Ju
  • Rust 安装,卸载,nightly/stable版本切换(全局或工作空间),提高下载速度

    版权所有 xff0c 转载前注明原址 时间 xff1a 2020年1月26日20 10 44 created by xff1a Hpbbs 文章目录 1 1 安装1 2 卸载1 3 更新1 4 Rust镜像源切换1 5 Rust night
  • Sql to Object VS Sql of Object

    文章目录 Java Object 中的 setter 与 getterLINQ 的定位 xff1a sql to objectSql of Object 的思维提出SQL of object 43 er实现SQLer Java Object
  • Ubuntu 桌面版无网络标识

    Ubuntu 配置网络的方式有两种 xff1a 通过桌面网络标识直接配置通过编辑配置文件配置 xff08 很麻烦 xff0c 而且不方便 xff09 因此 xff0c 下面介绍如何恢复桌面的网络标识 xff0c 以便于后续的网络配置 目录
  • repo sync 会自动切换本地分支与remote 分支的对应---如何自定义这种行为

    日后再写
  • [BugFix] [Android] DownloadManager使用流程问题导致的 下载下来的文件找不到

    DownloadManager使用流程错误导致的无法找到下载完成的文件 1 问题描述2 问题解决3 解决后的思考5 场景利用 1 问题描述 先提交 enqueue 请求 xff0c 后配置 DownloadManager span clas
  • View.post VS Handler.post的区别和使用场景对比

    View post 当对应的Widget View 没有attach到window的时候 xff0c 对应的Runnable会被提交到 ViewRootImpl RunQueue xff0c 如果已经attach的话 xff0c 会提交给U
  • Android 数据库安全:用户退出后,事务回滚日志依然保存有相关的数据信息

    详情 xff1a data data package name databases dday db data data package name databases dday db shm data data package name da
  • 关于IPhone无法收发短信---设置iphone短信中心号码

    这是个人拨打客服所收到解决短信 xff1a 尊敬的客户 xff0c 您好 xff01 如您反映的问题未解决或还有其他手机问题 xff0c 您可直接关注终端服务基地的官方微信公众号 xff1a cmcczdfw xff0c 随时随地获取便捷终
  • UART串口通信

    什么是串行通信 xff1f 将数据字节分成一位一位的形式在一条传输线上逐位地发送 优点 xff1a 成本低 xff0c 控制复杂 什么是异步通信 xff1f 异步通信是指通信的发送与接收设备使用各自的时钟控制数据的发送和接收过程 为使双方的
  • CAN总线数据帧

    CAN总线数据帧 1 xff0c 帧起始 xff08 SOF xff09 标识一个数据帧的开始 xff0c 用于帧同步 一个显性位 只有总线在空闲期间节点才能够发送SOF 2 ID 用于确定唯一一条报文 标准帧有11位 xff0c 扩展帧有
  • yolov3算法中关于loss={'yolo_loss': lambda y_true, y_pred: y_pred}的理解

    yolov3算法中关于loss 61 yolo loss lambda y true y pred y pred 的理解 参考文献 xff1a xff08 1 xff09 https www jianshu com p 7e45586c44
  • 【FreeRTOS】内存溢出检测

    Stack overflow detection FreeRTOS官方给了两种内存溢出检测方案 xff1a FreeRTOS stacks and stack overflow checking FreeRTOS is a portable

随机推荐

  • Linux实现简单的udp服务端和客户端(C/C++)

    udp server cpp include lt iostream gt include lt sys types h gt include lt sys socket h gt include lt unistd h gt includ
  • 开源日志库<log4cplus+VS2008使用>整理

    原创作品 xff0c 允许转载 xff0c 转载时请务必以超链接形式标明文章 原始出处 作者信息和本声明 否则将追究法律责任 http pyhcx blog 51cto com 713166 143549 本文出自 碧海笙箫 博客 xff0
  • 二.extern "C"

    extern关键字 xtern可以置于变量或者函数前 xff0c 以标示变量或者函数的定义在别的文件中 xff0c 提示编译器遇到此变量和函数时在其他模块中寻找其定义 此外extern也可用来进行链接指定 一 extern 34 C 34
  • Matlab2013b和Visual Studio 2013混合编程总结

    Matlab2013b和VisualStudio 2013混合编程总结 一 关于软件版本和安装的说明 一般来说 xff0c Matlab版本需高于或者等于VisualStudio的版本 综合版本功能和兼容问题 xff0c 我们选用了Matl
  • [linux] xlwt引起的字符串长度限制解除 & 递归深度限制解除 &Overflow问题

    1 xlwt引起的字符串长度限制 Exception String longer than 32767 characters 由于xlwt引起的excel写入的字符串 xff0c 长度不能大于32767 1 换txt写入 xff0c 或者用
  • 宏定义 宏参数

    带参数的宏定义 xff0c 利用宏参数创建字符串 运算符 看看以下两个宏定义 xff1a define PSQR x printf 34 The square of x is d n 34 x x define PSQR x printf
  • 舵机的PD控制

    PID 舵机以及差速PD调节 span class token keyword struct span span class token class name PID span span class token punctuation sp
  • 位置环与速度环的串级PID

    WHEELTEC的串级pid参考代码 span class token keyword float span Position KP span class token operator 61 span span class token nu
  • 智能车摄像头算法——圆环元素

    入环 1 入环的函数 xff08 1 xff09 搜上下边线 xff08 2 xff09 找凸起的弧 xff08 3 xff09 两点之间补线 xff08 4 xff09 判断上线是否单调 2 找圆环3 补线入环出环 1 入环的函数 xff
  • ROS的代价地图与AMCL定位原理

    地图服务与AMCL定位 costmap xff08 代价地图 xff09 AMCL定位 xff08 自适应蒙特卡罗定位 xff09 costmap xff08 代价地图 xff09 1 地图文件格式 xff1a 除了pgm xff08 便携
  • ROS路径规划算法

    ROS路径规划算法 全局路径规划Dijkstra算法A 算法 局部路径规划DWA算法TEB算法 全局路径规划 提供Dijkstra和A算法 xff0c 默认使用Dijkstra Dijkstra是把从出发点到终点的整个栅格地图上的所有的点
  • STM32常用功能配置

    STM32基本代码 设置外部中断定时器中断定时器产生pwmAD多通道转换DMA 43 AD扫描多通道转换iic协议读取数据SPI协议读取数据 设置外部中断 中断优先级分组 外部中断 AFIO作用 注意 xff1a 1 相同的Pin不能同时触
  • Ogre-渐变背景色(gradient background)的实现

    转载自 xff1a http blog csdn net hefee article details 6287341 背景色在ogre里面是通过ViewPort类中的setBackgroundColour xff08 xff09 这个成员函
  • Qt::WindowFlags

    查了些资料 xff0c 整理了一下 xff0c 以备查询 枚举类型 Qt WindowFlags低位的一个字节用于定义窗口部件的窗口类型 Qt WindowFlags的高位字节定义了窗口提示 xff0c 窗口提示能够进行位或操作 xff0c
  • java学习记录8

    什么是File 文件夹和文件 xff1a 文件夹是用来组织和管理磁盘文件的一种数据结构 文件是在电脑中 xff0c 以实现某种功能或某个软件的部分功能为目的定义的一个单位 xff0c 文件是由文件名和图标组成 xff0c 一种类型的文件具有
  • 保护模式编程之(一)——分段机制与GDT/LDT

    概述 xff1a 若想理解操作系统程序中的启动相关的部分 xff0c 必须要理解保护模式下的编程 xff0c 而分段机制是保护模式编程下的基础 另外 xff0c 由于实模式与保护模式的不同 xff0c 对保护模式下的分段机制更需要注意 同时
  • C++ 网络编程

    socket通信 xff1a socket 创建TCP套接字 bind 将套接字绑定到本地地址端口上 listen 监听端口 connect accept 接受用户请求 xff0c 返回对应此连接的新套接字 read write close
  • ROS学习(2)——rviz与gazebo问题记录

    ROS学习 xff08 2 xff09 rviz与gazebo问题记录 继续按照教程学习 xff0c 踩了很多坑 1 工作环境配置问题 实践6 2 4在rviz中显示模型时 xff0c 运行launch文件出现如下报错 原因 xff1a 出
  • VINS-Mono 代码详细解读——基础储备:在线Cam到IMU的外参标定 InitialEXRotation类

    本讲还是为了estimator类中最主要的函数processImage xff08 xff09 做知识储备 前面两讲知识储备主要讲了IMU预积分相关的integrationBase类以及图像特征点管理器feature manager cpp
  • VINS-Mono 代码详细解读——回环检测与重定位、四自由度位姿图优化

    本文主要介绍VINS的闭环检测重定位与位姿图优化部分 xff0c 作为系列文章的最后一节 回环检测的关键就是如何有效检测出相机曾经经过同一个地方 xff0c 这样可以避免较大的累积误差 xff0c 使得当前帧和之前的某一帧迅速建立约束 xf