VINS(七)estimator_node 数据对齐 imu预积分 vision

2023-05-16

首先通过vins_estimator mode监听几个Topic(频率2000Hz),将imu数据,feature数据,raw_image数据(用于回环检测)通过各自的回调函数封装起来


ros::Subscriber sub_imu = n.subscribe(IMU_TOPIC, 2000, imu_callback, ros::TransportHints().tcpNoDelay());
ros::Subscriber sub_image = n.subscribe("/feature_tracker/feature", 2000, feature_callback);
ros::Subscriber sub_raw_image = n.subscribe(IMAGE_TOPIC, 2000, raw_image_callback);  

imu_buf.push(imu_msg);
feature_buf.push(feature_msg);
image_buf.push(make_pair(img_ptr->image, img_msg->header.stamp.toSec()));  

然后开启处理measurement的线程


std::thread measurement_process{process};  

process()函数中,首先将获取的传感器数据imu_buf feature_buf对齐,注意这里只保证了相邻的feature数据之间有完整的imu数据,并不能保证imu和feature数据的精确对齐


// multiple IMU measurements and only one vision(features) measurements
std::vector<std::pair<std::vector<sensor_msgs::ImuConstPtr>, sensor_msgs::PointCloudConstPtr>>
getMeasurements()
{
    std::vector<std::pair<std::vector<sensor_msgs::ImuConstPtr>, sensor_msgs::PointCloudConstPtr>> measurements;

    while (true)
    {
        if (imu_buf.empty() || feature_buf.empty())
            return measurements;

        // synchronize, if strictly synchronize, should change to ">="
        // end up with : imu_buf.front()->header.stamp < feature_buf.front()->header.stamp
        
        // 1. should have overlap
        if (!(imu_buf.back()->header.stamp > feature_buf.front()->header.stamp))
        {
            ROS_WARN("wait for imu, only should happen at the beginning");
            sum_of_wait++;
            return measurements;
        }

        // 2. should have complete imu measurements between two feature_buf msg
        if (!(imu_buf.front()->header.stamp < feature_buf.front()->header.stamp))
        {
            ROS_WARN("throw img, only should happen at the beginning");
            feature_buf.pop();
            continue;
        }
        
        sensor_msgs::PointCloudConstPtr img_msg = feature_buf.front();
        feature_buf.pop();

        std::vector<sensor_msgs::ImuConstPtr> IMUs;
        while (imu_buf.front()->header.stamp <= img_msg->header.stamp)
        {
            IMUs.emplace_back(imu_buf.front());
            imu_buf.pop();
        }

        measurements.emplace_back(IMUs, img_msg);
    }
    return measurements;
}  

接下来进入对measurements数据的处理:

处理imu数据的接口函数是processIMU()

处理vision数据的借口函数是processImage()

(一)IMU

1. 核心API:


midPointIntegration(_dt, acc_0, gyr_0, _acc_1, _gyr_1, delta_p, delta_q, delta_v,
                            linearized_ba, linearized_bg,
                            result_delta_p, result_delta_q, result_delta_v,
                            result_linearized_ba, result_linearized_bg, 1);  

其中,0代表上次测量值,1代表当前测量值,delta_p,delta_q,delta_v代表相对预积分初始参考系的位移,旋转四元数,以及速度(例如,从k帧预积分到k+1帧,则参考系是k帧的imu坐标系)

对应实现的是公式:

相应的离散实现使用Euler,Mid-point,或者龙格库塔(RK4)数值积分方法。

Euler方法如下:

2. 求状态向量对bias的Jacobian,当bias变化较小时,使用Jacobian去更新状态;否则需要以当前imu为参考系,重新预积分,对应repropagation()。同时,需要计算error state model中误差传播方程的系数矩阵F和V:


    // pre-integration 
    // time interval of two imu; last and current imu measurements; p,q,v relate to local frame; ba and bg; propagated p,q,v,ba,bg; 
    // whether to update Jacobian and calculate F,V
    void midPointIntegration(double _dt, 
                            const Eigen::Vector3d &_acc_0, const Eigen::Vector3d &_gyr_0,
                            const Eigen::Vector3d &_acc_1, const Eigen::Vector3d &_gyr_1,
                            const Eigen::Vector3d &delta_p, const Eigen::Quaterniond &delta_q, const Eigen::Vector3d &delta_v,
                            const Eigen::Vector3d &linearized_ba, const Eigen::Vector3d &linearized_bg,
                            Eigen::Vector3d &result_delta_p, Eigen::Quaterniond &result_delta_q, Eigen::Vector3d &result_delta_v,
                            Eigen::Vector3d &result_linearized_ba, Eigen::Vector3d &result_linearized_bg, bool update_jacobian)
    {
        //ROS_INFO("midpoint integration");
        // mid-point integration with bias = 0
        Vector3d un_acc_0 = delta_q * (_acc_0 - linearized_ba); 
        Vector3d un_gyr = 0.5 * (_gyr_0 + _gyr_1) - linearized_bg;
        result_delta_q = delta_q * Quaterniond(1, un_gyr(0) * _dt / 2, un_gyr(1) * _dt / 2, un_gyr(2) * _dt / 2);
        Vector3d un_acc_1 = result_delta_q * (_acc_1 - linearized_ba);
        Vector3d un_acc = 0.5 * (un_acc_0 + un_acc_1);
        result_delta_p = delta_p + delta_v * _dt + 0.5 * un_acc * _dt * _dt;
        result_delta_v = delta_v + un_acc * _dt;
        // ba and bg donot change
        result_linearized_ba = linearized_ba;
        result_linearized_bg = linearized_bg;

        // jacobian to bias, used when the bias changes slightly and no need of repropagation
        if(update_jacobian)
        {
            // same as un_gyr, gyrometer reference to the local frame bk
            Vector3d w_x = 0.5 * (_gyr_0 + _gyr_1) - linearized_bg;
            
            // last acceleration measurement
            Vector3d a_0_x = _acc_0 - linearized_ba;
            // current acceleration measurement
            Vector3d a_1_x = _acc_1 - linearized_ba;
            
            // used for cross-product
            // pay attention to derivation of matrix product
            Matrix3d R_w_x, R_a_0_x, R_a_1_x;

            R_w_x<<0, -w_x(2), w_x(1),
                w_x(2), 0, -w_x(0),
                -w_x(1), w_x(0), 0;
            R_a_0_x<<0, -a_0_x(2), a_0_x(1),
                a_0_x(2), 0, -a_0_x(0),
                -a_0_x(1), a_0_x(0), 0;
            R_a_1_x<<0, -a_1_x(2), a_1_x(1),
                a_1_x(2), 0, -a_1_x(0),
                -a_1_x(1), a_1_x(0), 0;

            // error state model
            // should use discrete format and mid-point approximation
            MatrixXd F = MatrixXd::Zero(15, 15);
            F.block<3, 3>(0, 0) = Matrix3d::Identity();
            F.block<3, 3>(0, 3) = -0.25 * delta_q.toRotationMatrix() * R_a_0_x * _dt * _dt + 
                                  -0.25 * result_delta_q.toRotationMatrix() * R_a_1_x * (Matrix3d::Identity() - R_w_x * _dt) * _dt * _dt;
            F.block<3, 3>(0, 6) = MatrixXd::Identity(3,3) * _dt;
            F.block<3, 3>(0, 9) = -0.25 * (delta_q.toRotationMatrix() + result_delta_q.toRotationMatrix()) * _dt * _dt;
            F.block<3, 3>(0, 12) = -0.25 * result_delta_q.toRotationMatrix() * R_a_1_x * _dt * _dt * -_dt;
            F.block<3, 3>(3, 3) = Matrix3d::Identity() - R_w_x * _dt;
            F.block<3, 3>(3, 12) = -1.0 * MatrixXd::Identity(3,3) * _dt;
            F.block<3, 3>(6, 3) = -0.5 * delta_q.toRotationMatrix() * R_a_0_x * _dt + 
                                  -0.5 * result_delta_q.toRotationMatrix() * R_a_1_x * (Matrix3d::Identity() - R_w_x * _dt) * _dt;
            F.block<3, 3>(6, 6) = Matrix3d::Identity();
            F.block<3, 3>(6, 9) = -0.5 * (delta_q.toRotationMatrix() + result_delta_q.toRotationMatrix()) * _dt;
            F.block<3, 3>(6, 12) = -0.5 * result_delta_q.toRotationMatrix() * R_a_1_x * _dt * -_dt;
            F.block<3, 3>(9, 9) = Matrix3d::Identity();
            F.block<3, 3>(12, 12) = Matrix3d::Identity();

            MatrixXd V = MatrixXd::Zero(15,18);
            V.block<3, 3>(0, 0) =  0.25 * delta_q.toRotationMatrix() * _dt * _dt;
            V.block<3, 3>(0, 3) =  0.25 * -result_delta_q.toRotationMatrix() * R_a_1_x  * _dt * _dt * 0.5 * _dt;
            V.block<3, 3>(0, 6) =  0.25 * result_delta_q.toRotationMatrix() * _dt * _dt;
            V.block<3, 3>(0, 9) =  V.block<3, 3>(0, 3);
            V.block<3, 3>(3, 3) =  0.5 * MatrixXd::Identity(3,3) * _dt;
            V.block<3, 3>(3, 9) =  0.5 * MatrixXd::Identity(3,3) * _dt;
            V.block<3, 3>(6, 0) =  0.5 * delta_q.toRotationMatrix() * _dt;
            V.block<3, 3>(6, 3) =  0.5 * -result_delta_q.toRotationMatrix() * R_a_1_x  * _dt * 0.5 * _dt;
            V.block<3, 3>(6, 6) =  0.5 * result_delta_q.toRotationMatrix() * _dt;
            V.block<3, 3>(6, 9) =  V.block<3, 3>(6, 3);
            V.block<3, 3>(9, 12) = MatrixXd::Identity(3,3) * _dt;
            V.block<3, 3>(12, 15) = MatrixXd::Identity(3,3) * _dt;

            //step_jacobian = F;
            //step_V = V;
            jacobian = F * jacobian;
            covariance = F * covariance * F.transpose() + V * noise * V.transpose();
        }
    }  

 

 

(二)Vision

 首先判断该帧是否关键帧:


    if (f_manager.addFeatureCheckParallax(frame_count, image))
        marginalization_flag = MARGIN_OLD;
    else
        marginalization_flag = MARGIN_SECOND_NEW;  

关键帧的判断依据是rotation-compensated过后的parallax足够大,并且tracking上的feature足够多;关键帧会保留在当前Sliding Window中,marginalize掉Sliding Window中最旧的状态,如果是非关键帧则优先marginalize掉。

1. 标定外参旋转矩阵


initial_ex_rotation.CalibrationExRotation(corres, pre_integrations[frame_count]->delta_q, calib_ric)  

其中


pre_integrations[frame_count]->delta_q  

是使用imu pre-integration获取的旋转矩阵,会和视觉跟踪求解fundamentalMatrix分解后获得的旋转矩阵构建约束方程,从而标定出外参旋转矩阵。

2. 线性初始化


    if (solver_flag == INITIAL)
    {
        if (frame_count == WINDOW_SIZE)
        {
            bool result = false;
            if( ESTIMATE_EXTRINSIC != 2 && (header.stamp.toSec() - initial_timestamp) > 0.1)
            {
               result = initialStructure();
               initial_timestamp = header.stamp.toSec();
            }
            if(result)
            {
                solver_flag = NON_LINEAR;
                solveOdometry();
                slideWindow();
                f_manager.removeFailures();
                ROS_INFO("Initialization finish!");
                last_R = Rs[WINDOW_SIZE];
                last_P = Ps[WINDOW_SIZE];
                last_R0 = Rs[0];
                last_P0 = Ps[0];
                
            }
            else
                slideWindow();
        }
        else
            frame_count++;
    }  

3. 非线性优化


    else
    {
        TicToc t_solve;
        solveOdometry();
        ROS_DEBUG("solver costs: %fms", t_solve.toc());

        if (failureDetection())
        {
            ROS_WARN("failure detection!");
            failure_occur = 1;
            clearState();
            setParameter();
            ROS_WARN("system reboot!");
            return;
        }

        TicToc t_margin;
        slideWindow();
        f_manager.removeFailures();
        ROS_DEBUG("marginalization costs: %fms", t_margin.toc());
        // prepare output of VINS
        key_poses.clear();
        for (int i = 0; i <= WINDOW_SIZE; i++)
            key_poses.push_back(Ps[i]);

        last_R = Rs[WINDOW_SIZE];
        last_P = Ps[WINDOW_SIZE];
        last_R0 = Rs[0];
        last_P0 = Ps[0];
    }  

 主要的初始化,非线性优化的api均在这里,因此放在后面去说明。

转载于:https://www.cnblogs.com/shang-slam/p/7144468.html

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

VINS(七)estimator_node 数据对齐 imu预积分 vision 的相关文章

  • Node处理csv文件(利用csv-parse读取指定字符串内的文件片段)

    需求 读取一个csv文件 需要从指定字符串开始读取至指定字符串结束 由于csv文件可能使用不同环境打开编辑过 末尾包含很多多余的分隔逗号 去除这些逗号 使用 Stream const parse require csv parse cons
  • Node.js 下载安装环境配置 - 图文版

    Node js 是一个开源 跨平台的 JavaScript 运行时环境 一 介绍 1 官方文档 1 中文文档 Node js 中文网 2 英文文档 Node js 二 下载 1 中文 2 英文 编辑三 安装 1 新建一个文件夹作为安装路径
  • PID算法(没办法完全理解的东西)

    快速 P 准确 I 稳定 D P Proportion 比例 就是输入偏差乘以一个常数 I Integral 积分 就是对输入偏差进行积分运算 D Derivative 微分 对输入偏差进行微分运算 输入偏差 读出的被控制对象的值 设定值
  • node request 解决请求时 有时候 content-length 获取不到

    今天使用了 request 模块的时候 想获取每次请求的大小 以方便判断下载进度 网速等等 然后 content length 头总是获取不到 下面给出解决方法 request 模块的使用方法见 api 文档 https github co
  • 在node中使用es7

    今天学写了体验异步的终极解决方案 ES7的Async Await这篇文章 发现作者是用 es7 的语法写 node 所以顺便学习了一下如何在 node 中使用 es7 的语法 记录一下 首先安装 babel cli yarn add bab
  • An Introduction for IMU 2 - IMU数据融合与姿态解算

    在上一篇博客中 我们已经介绍了IMU的内部工作原理 以及如何通过Arduino读取MPU6050的数据 虽然可以从DMP直接读取姿态角 但其数据返回的频率相对较低 同时由于DMP库不是开源的 其内部的工作原理 输出姿态角的准确性都不清楚 而
  • Node.js——回调函数及事件处理机制

    目录 回调函数 定义 理解 事件处理机制 补充 回调函数 定义 什么是回调函数呢 通俗的讲 将一个函数A作为参数传递给函数B 在函数B内对函数A进行调用 函数A就是回调函数 Node js 异步编程的直接体现就是回调 回调函数在完成任务后就
  • IMU的ROS调试开发工具包:imu_tools

    目录 imu tool包 问题 参数配置便利性问题 实例 调试microstrain 3dm gx5 25 imu 问题 发布的imu姿态与实际imu姿态不一致问题 imu tool包 http wiki ros org imu tools
  • Node.js 从零开发 web server博客项目[koa2重构博客项目]

    web server博客项目 Node js 从零开发 web server博客项目 项目介绍 Node js 从零开发 web server博客项目 接口 Node js 从零开发 web server博客项目 数据存储 Node js
  • nodejs 控制台美化 console-color-mr

    console color mr插件可以让node控制台输出带有颜色 是一个不错的插件 通过颜色可以更直观的分析程序bug 一 使用 npm install D console color mr 方法一 import console col
  • node连接mysql实现带分页列表多条件模糊查询效果-新手教程

    前言 使用node连接mysql 这里是模糊查询方法完整流程 第一 安装我们的express脚手架 入口 第二 在根目录下创建model文件夹 里面放两个文件 1 mysql config js 这里放的是我们的数据库配置 配置链接数据库参
  • nginx基本介绍(安装、常用命令、反向代理)

    文章目录 引言 一 nginx是什么 二 nginx的下载和安装 1 下载 2 windows下安装 3 运行 4 外部服务器无法访问问题 三 nginx的常用命令 四 nginx config 五 FileZilla 1 什么是FileZ
  • Node.js 版本管理工具 n 使用指南

    Node js 版本更新很快 目前 node v20 x 已经发布 我们在使用时避免不了会需要切换不同的 Node js 的版本来使用不同版本的特性 所以就出现了像 windows 上的 nvm MacOS 上的 n 工具 本文就介绍一下如
  • 初识pnpm

    初识pnpm 介绍 pnpm和npm yarn一样 都是包管理器 但是pnpm节约磁盘空间并且安装很快 所有的报会存储在硬盘的同一个位置 多个项目使用了同一个包时 在pnpm中他们是公用的 只会存储一遍 下次需要用到这个包时就会从硬盘中查找
  • 四元素与旋转矩阵

    如何描述三维空间中刚体的旋转 是个有趣的问题 具体地说 就是刚体上的任意一个点P x y z 围绕过原点的轴 i j k 旋转 求旋转后的点P x y z 旋转矩阵 旋转矩阵乘以点P的齐次坐标 得到旋转后的点P 因此旋转矩阵可以描述旋转 x
  • 解决node.js+MYSQL读/写date类型数据有异样,且相差8个小时的问题

    既将读 写格式为 2021 05 04T16 00 00 000Z 的数据 转换为本地日期时间 2021 05 05 格式 一 读取异样处理 例如 在数据库中date类型数据原本为 2021 05 05 但是直接打印出来确是下面这样 dat
  • Nodejs版本管理工具mvn部署

    部署mvn curl o https raw githubusercontent com creationix nvm v0 34 0 install sh bash 添加环境变量 vim zshrc export NVM DIR HOME
  • 足部IMU在复杂场景中行走定位

    随着微机电系统 MEMS 技术的快速发展 基于MEMS的惯性导航系统 INS 在任意环境的基站定位方面发挥着至关重要的作用 惯性导航具有自主性强 定位频率高 功耗低 实时性强等特点 因此更适合单兵作战 反恐行动 应急救援 消防救援等环境未知
  • 人眼注视检测:识别用户正在看板上的位置[关闭]

    Closed 这个问题是无法重现或由拼写错误引起 help closed questions 目前不接受答案 我正在开发一个项目 上面有板和相机 目标是识别正在看黑板的学生 并确定他们视线的位置 在黑板上 目前 我计划从以下几个方面来应对挑
  • 使用Python的工业视觉相机[关闭]

    就目前情况而言 这个问题不太适合我们的问答形式 我们希望答案得到事实 参考资料或专业知识的支持 但这个问题可能会引发辩论 争论 民意调查或扩展讨论 如果您觉得这个问题可以改进并可能重新开放 访问帮助中心 help reopen questi

随机推荐