第三篇 视觉里程计(VO)的初始化过程以及openvslam中的相关实现详解

视觉里程计(Visual Odometry, VO),通过使用相机提供的连续帧图像信息(以及局部地图,先不考虑)来估计相邻帧的相机运动,将这些相对运行转换为以第一帧为参考的位姿信息,就得到了相机载体(假设统一的刚体)的里程信息。先上一张本文主要内容的框图:
1779232-20190906154117746-2053129800.png

初始化实例

在实例化跟踪器的时候会实例化一个初始化实例,有一些比较重要的参数需要注意下,看代码注释以及初始值,参数值也可以在yaml文件中自定义。

// src/openvslam/module/initializer.h:83
//! max number of iterations of RANSAC (only for monocular initializer)
const unsigned int num_ransac_iters_;
//! min number of triangulated pts
const unsigned int min_num_triangulated_;
//! min parallax (only for monocular initializer)
const float parallax_deg_thr_;
//! reprojection error threshold (only for monocular initializer)
const float reproj_err_thr_;
//! max number of iterations of BA (only for monocular initializer)
const unsigned int num_ba_iters_;
//! initial scaling factor (only for monocular initializer)
const float scaling_factor_;


// src/openvslam/module/initializer.cc:16
initializer::initializer(const camera::setup_type_t setup_type,
                         data::map_database* map_db, data::bow_database* bow_db,
                         const YAML::Node& yaml_node)
        : setup_type_(setup_type), map_db_(map_db), bow_db_(bow_db),
          num_ransac_iters_(yaml_node["Initializer.num_ransac_iterations"].as<unsigned int>(100)),
          min_num_triangulated_(yaml_node["Initializer.num_min_triangulated_pts"].as<unsigned int>(50)),
          parallax_deg_thr_(yaml_node["Initializer.parallax_deg_threshold"].as<float>(1.0)),
          reproj_err_thr_(yaml_node["Initializer.reprojection_error_threshold"].as<float>(4.0)),
          num_ba_iters_(yaml_node["Initializer.num_ba_iterations"].as<unsigned int>(20)),
          scaling_factor_(yaml_node["Initializer.scaling_factor"].as<float>(1.0)) {
    spdlog::debug("CONSTRUCT: module::initializer");
}

使用不同的相机类型,初始化的方法也不相同,openvslam使用了perspective和bearing_vector两种初始化方法。

// src/openvslam/module/initializer.cc:91
void initializer::create_initializer(data::frame& curr_frm) {
    // 将当前帧设置为初始化过程中的参考帧
    init_frm_ = data::frame(curr_frm);

    // 将当前帧的特征点当作previously matched coordinates
    prev_matched_coords_.resize(init_frm_.undist_keypts_.size());
    for (unsigned int i = 0; i < init_frm_.undist_keypts_.size(); ++i) {
        prev_matched_coords_.at(i) = init_frm_.undist_keypts_.at(i).pt;
    }

    // initialize matchings (init_idx -> curr_idx)
    std::fill(init_matches_.begin(), init_matches_.end(), -1);

    // build a initializer
    initializer_.reset(nullptr);
    switch (
  • 0
    点赞
  • 1
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值