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

  1. ros::Subscriber sub_imu = n.subscribe(IMU_TOPIC, , imu_callback, ros::TransportHints().tcpNoDelay());
  2. ros::Subscriber sub_image = n.subscribe("/feature_tracker/feature", , feature_callback);
  3. ros::Subscriber sub_raw_image = n.subscribe(IMAGE_TOPIC, , raw_image_callback);
  1. imu_buf.push(imu_msg);
  2. feature_buf.push(feature_msg);
  3. image_buf.push(make_pair(img_ptr->image, img_msg->header.stamp.toSec()));

然后开启处理measurement的线程

  1. std::thread measurement_process{process};

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

  1. // multiple IMU measurements and only one vision(features) measurements
  2. std::vector<std::pair<std::vector<sensor_msgs::ImuConstPtr>, sensor_msgs::PointCloudConstPtr>>
  3. getMeasurements()
  4. {
  5. std::vector<std::pair<std::vector<sensor_msgs::ImuConstPtr>, sensor_msgs::PointCloudConstPtr>> measurements;
  6.  
  7. while (true)
  8. {
  9. if (imu_buf.empty() || feature_buf.empty())
  10. return measurements;
  11.  
  12. // synchronize, if strictly synchronize, should change to ">="
  13. // end up with : imu_buf.front()->header.stamp < feature_buf.front()->header.stamp
  14.  
  15. // 1. should have overlap
  16. if (!(imu_buf.back()->header.stamp > feature_buf.front()->header.stamp))
  17. {
  18. ROS_WARN("wait for imu, only should happen at the beginning");
  19. sum_of_wait++;
  20. return measurements;
  21. }
  22.  
  23. // 2. should have complete imu measurements between two feature_buf msg
  24. if (!(imu_buf.front()->header.stamp < feature_buf.front()->header.stamp))
  25. {
  26. ROS_WARN("throw img, only should happen at the beginning");
  27. feature_buf.pop();
  28. continue;
  29. }
  30.  
  31. sensor_msgs::PointCloudConstPtr img_msg = feature_buf.front();
  32. feature_buf.pop();
  33.  
  34. std::vector<sensor_msgs::ImuConstPtr> IMUs;
  35. while (imu_buf.front()->header.stamp <= img_msg->header.stamp)
  36. {
  37. IMUs.emplace_back(imu_buf.front());
  38. imu_buf.pop();
  39. }
  40.  
  41. measurements.emplace_back(IMUs, img_msg);
  42. }
  43. return measurements;
  44. }

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

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

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

(一)IMU

1. 核心API:

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

其中,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:

  1. // pre-integration
  2. // 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;
  3. // whether to update Jacobian and calculate F,V
  4. void midPointIntegration(double _dt,
  5. const Eigen::Vector3d &_acc_0, const Eigen::Vector3d &_gyr_0,
  6. const Eigen::Vector3d &_acc_1, const Eigen::Vector3d &_gyr_1,
  7. const Eigen::Vector3d &delta_p, const Eigen::Quaterniond &delta_q, const Eigen::Vector3d &delta_v,
  8. const Eigen::Vector3d &linearized_ba, const Eigen::Vector3d &linearized_bg,
  9. Eigen::Vector3d &result_delta_p, Eigen::Quaterniond &result_delta_q, Eigen::Vector3d &result_delta_v,
  10. Eigen::Vector3d &result_linearized_ba, Eigen::Vector3d &result_linearized_bg, bool update_jacobian)
  11. {
  12. //ROS_INFO("midpoint integration");
  13. // mid-point integration with bias = 0
  14. Vector3d un_acc_0 = delta_q * (_acc_0 - linearized_ba);
  15. Vector3d un_gyr = 0.5 * (_gyr_0 + _gyr_1) - linearized_bg;
  16. result_delta_q = delta_q * Quaterniond(, un_gyr() * _dt / , un_gyr() * _dt / , un_gyr() * _dt / );
  17. Vector3d un_acc_1 = result_delta_q * (_acc_1 - linearized_ba);
  18. Vector3d un_acc = 0.5 * (un_acc_0 + un_acc_1);
  19. result_delta_p = delta_p + delta_v * _dt + 0.5 * un_acc * _dt * _dt;
  20. result_delta_v = delta_v + un_acc * _dt;
  21. // ba and bg donot change
  22. result_linearized_ba = linearized_ba;
  23. result_linearized_bg = linearized_bg;
  24.  
  25. // jacobian to bias, used when the bias changes slightly and no need of repropagation
  26. if(update_jacobian)
  27. {
  28. // same as un_gyr, gyrometer reference to the local frame bk
  29. Vector3d w_x = 0.5 * (_gyr_0 + _gyr_1) - linearized_bg;
  30.  
  31. // last acceleration measurement
  32. Vector3d a_0_x = _acc_0 - linearized_ba;
  33. // current acceleration measurement
  34. Vector3d a_1_x = _acc_1 - linearized_ba;
  35.  
  36. // used for cross-product
  37. // pay attention to derivation of matrix product
  38. Matrix3d R_w_x, R_a_0_x, R_a_1_x;
  39.  
  40. R_w_x<<, -w_x(), w_x(),
  41. w_x(), , -w_x(),
  42. -w_x(), w_x(), ;
  43. R_a_0_x<<, -a_0_x(), a_0_x(),
  44. a_0_x(), , -a_0_x(),
  45. -a_0_x(), a_0_x(), ;
  46. R_a_1_x<<, -a_1_x(), a_1_x(),
  47. a_1_x(), , -a_1_x(),
  48. -a_1_x(), a_1_x(), ;
  49.  
  50. // error state model
  51. // should use discrete format and mid-point approximation
  52. MatrixXd F = MatrixXd::Zero(, );
  53. F.block<, >(, ) = Matrix3d::Identity();
  54. F.block<, >(, ) = -0.25 * delta_q.toRotationMatrix() * R_a_0_x * _dt * _dt +
  55. -0.25 * result_delta_q.toRotationMatrix() * R_a_1_x * (Matrix3d::Identity() - R_w_x * _dt) * _dt * _dt;
  56. F.block<, >(, ) = MatrixXd::Identity(,) * _dt;
  57. F.block<, >(, ) = -0.25 * (delta_q.toRotationMatrix() + result_delta_q.toRotationMatrix()) * _dt * _dt;
  58. F.block<, >(, ) = -0.25 * result_delta_q.toRotationMatrix() * R_a_1_x * _dt * _dt * -_dt;
  59. F.block<, >(, ) = Matrix3d::Identity() - R_w_x * _dt;
  60. F.block<, >(, ) = -1.0 * MatrixXd::Identity(,) * _dt;
  61. F.block<, >(, ) = -0.5 * delta_q.toRotationMatrix() * R_a_0_x * _dt +
  62. -0.5 * result_delta_q.toRotationMatrix() * R_a_1_x * (Matrix3d::Identity() - R_w_x * _dt) * _dt;
  63. F.block<, >(, ) = Matrix3d::Identity();
  64. F.block<, >(, ) = -0.5 * (delta_q.toRotationMatrix() + result_delta_q.toRotationMatrix()) * _dt;
  65. F.block<, >(, ) = -0.5 * result_delta_q.toRotationMatrix() * R_a_1_x * _dt * -_dt;
  66. F.block<, >(, ) = Matrix3d::Identity();
  67. F.block<, >(, ) = Matrix3d::Identity();
  68.  
  69. MatrixXd V = MatrixXd::Zero(,);
  70. V.block<, >(, ) = 0.25 * delta_q.toRotationMatrix() * _dt * _dt;
  71. V.block<, >(, ) = 0.25 * -result_delta_q.toRotationMatrix() * R_a_1_x * _dt * _dt * 0.5 * _dt;
  72. V.block<, >(, ) = 0.25 * result_delta_q.toRotationMatrix() * _dt * _dt;
  73. V.block<, >(, ) = V.block<, >(, );
  74. V.block<, >(, ) = 0.5 * MatrixXd::Identity(,) * _dt;
  75. V.block<, >(, ) = 0.5 * MatrixXd::Identity(,) * _dt;
  76. V.block<, >(, ) = 0.5 * delta_q.toRotationMatrix() * _dt;
  77. V.block<, >(, ) = 0.5 * -result_delta_q.toRotationMatrix() * R_a_1_x * _dt * 0.5 * _dt;
  78. V.block<, >(, ) = 0.5 * result_delta_q.toRotationMatrix() * _dt;
  79. V.block<, >(, ) = V.block<, >(, );
  80. V.block<, >(, ) = MatrixXd::Identity(,) * _dt;
  81. V.block<, >(, ) = MatrixXd::Identity(,) * _dt;
  82.  
  83. //step_jacobian = F;
  84. //step_V = V;
  85. jacobian = F * jacobian;
  86. covariance = F * covariance * F.transpose() + V * noise * V.transpose();
  87. }
  88. }

(二)Vision

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

  1. if (f_manager.addFeatureCheckParallax(frame_count, image))
  2. marginalization_flag = MARGIN_OLD;
  3. else
  4. marginalization_flag = MARGIN_SECOND_NEW;

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

1. 标定外参旋转矩阵

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

其中

  1. pre_integrations[frame_count]->delta_q

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

2. 线性初始化

  1. if (solver_flag == INITIAL)
  2. {
  3. if (frame_count == WINDOW_SIZE)
  4. {
  5. bool result = false;
  6. if( ESTIMATE_EXTRINSIC != && (header.stamp.toSec() - initial_timestamp) > 0.1)
  7. {
  8. result = initialStructure();
  9. initial_timestamp = header.stamp.toSec();
  10. }
  11. if(result)
  12. {
  13. solver_flag = NON_LINEAR;
  14. solveOdometry();
  15. slideWindow();
  16. f_manager.removeFailures();
  17. ROS_INFO("Initialization finish!");
  18. last_R = Rs[WINDOW_SIZE];
  19. last_P = Ps[WINDOW_SIZE];
  20. last_R0 = Rs[];
  21. last_P0 = Ps[];
  22.  
  23. }
  24. else
  25. slideWindow();
  26. }
  27. else
  28. frame_count++;
  29. }

3. 非线性优化

  1. else
  2. {
  3. TicToc t_solve;
  4. solveOdometry();
  5. ROS_DEBUG("solver costs: %fms", t_solve.toc());
  6.  
  7. if (failureDetection())
  8. {
  9. ROS_WARN("failure detection!");
  10. failure_occur = ;
  11. clearState();
  12. setParameter();
  13. ROS_WARN("system reboot!");
  14. return;
  15. }
  16.  
  17. TicToc t_margin;
  18. slideWindow();
  19. f_manager.removeFailures();
  20. ROS_DEBUG("marginalization costs: %fms", t_margin.toc());
  21. // prepare output of VINS
  22. key_poses.clear();
  23. for (int i = ; i <= WINDOW_SIZE; i++)
  24. key_poses.push_back(Ps[i]);
  25.  
  26. last_R = Rs[WINDOW_SIZE];
  27. last_P = Ps[WINDOW_SIZE];
  28. last_R0 = Rs[];
  29. last_P0 = Ps[];
  30. }

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

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

  1. 转载泡泡机器人——IMU预积分总结与公式推导1

    IMU预积分技术最早由T Lupton于12年提出[1],C Forster于15年[2][3][4]将其进一步拓展到李代数上,形成了一套优雅的理论体系.Forster将IMU预积分在开源因子图优化库 ...

  2. 转载泡泡机器人——IMU预积分总结与公式推导2

    本文为IMU预积分总结与公式推导系列技术报告的第二篇. 承接第一篇的内容,本篇将推导IMU预积分的测量值,并分析其测量误差的分布形式. 传统捷联惯性导航的递推算法,以初始状态为基础,利用IMU测量得到 ...

  3. IMU 预积分推导

    给 StereoDSO 加 IMU,想直接用 OKVIS 的代码,但是有点看不懂.知乎上郑帆写的文章<四元数矩阵与 so(3) 左右雅可比>提到 OKVIS 的预积分是使用四元数,而预积分 ...

  4. VINS(三)IMU预积分

    IMU的数据频率一般远高于视觉,在视觉两帧k,k+1之间通常会有>10组IMU数据.IMU的数据通过积分,可以获取当前位姿(p位置,q四元数表达的姿态).瞬时速度等参数. 在VIO中,如果参考世 ...

  5. IMU预积分

    https://www.sohu.com/a/242760307_715754 http://www.sohu.com/a/243155537_715754 https://www.sohu.com/ ...

  6. SLAM+语音机器人DIY系列:(三)感知与大脑——2.带自校准九轴数据融合IMU惯性传感器

    摘要 在我的想象中机器人首先应该能自由的走来走去,然后应该能流利的与主人对话.朝着这个理想,我准备设计一个能自由行走,并且可以与人语音对话的机器人.实现的关键是让机器人能通过传感器感知周围环境,并通过 ...

  7. 结构体的数据对齐 #pragma浅谈

    之前若是有人拿个结构体或者联合体问我这个结构占用了多少字节的内存,我一定觉得这个人有点low, 直到某某公司的一个实习招聘模拟题的出现,让我不得不重新审视这个问题, 该问题大致如下: typedef ...

  8. 数据对齐 posix_memalign 函数详解

    对齐 数 据的对齐(alignment)是指数据的地址和由硬件条件决定的内存块大小之间的关系.一个变量的地址是它大小的倍数的时候,这就叫做自然对齐 (naturally aligned).例如,对于一 ...

  9. 从零开始一起学习SLAM | 用四元数插值来对齐IMU和图像帧

    视觉 Vs. IMU 小白:师兄,好久没见到你了啊,我最近在看IMU(Inertial Measurement Unit,惯性导航单元)相关的东西,正好有问题求助啊 师兄:又遇到啥问题啦? 小白:是这 ...

随机推荐

  1. Hibernate多对一关联关系

    两个持久化类.Customer 和 OrderForm Customer 类. package com.zcd.hibernate.manyToOne; public class Customer { ...

  2. BZOJ2816:[ZJOI2012]网络(LCT)

    Description 有一个无向图G,每个点有个权值,每条边有一个颜色.这个无向图满足以下两个条件: 对于任意节点连出去的边中,相同颜色的边不超过两条. 图中不存在同色的环,同色的环指相同颜色的边构 ...

  3. Jupyter Notebook 设置黑色背景主题、字体大小、代码自动补全

    1.背景主题.字体大小设置 安装Jupyter主题: pip install jupyterthemes 然后,更新Jupyter主题: pip install --upgrade jupyterth ...

  4. es6之proxy和reflect

    一.proxy //Proxy和Reflect //供应商 let obj={ time:"2017-11-21", name:"net", _r:123 } ...

  5. 绘图驱动-OSD原理2

    转载自:http://blog.pfan.cn/programming/21209.html 现在已经可以通过修改存储单元内容来改变OSD的像素,但还有个关键的问题是如何根据需要来进行操作,即如何将某 ...

  6. Zookeeper简介和安装(四)

    一.简介: Zookeeper是一个分布式协调服务,提供的服务如下: 命名服务:类似于DNS,但仅对于节点 配置管理:服务配置信息的管理 集群管理:Dubbo使用Zookeeper实现服务治理 分布式 ...

  7. 谨慎修改Oracle数据库字符集(UTF8<->ZHS16GBK)

      Preface       Today,I'm gonna say something what is related with the character set in Oracle datab ...

  8. oracle计算某个表中数据所占表空间的比例

    要求计算某个表所占表空间的大小,网上查了些资料用到了oracle的3个视图.具体sql如下 select segment_name as tablename, round(bytes / (selec ...

  9. Ajax请求(415 Unsupported Media Type)

    Unsupported media type-415(不支持的媒体类型) 该错误类型是后台接收参数为json类型的,然而ajax提交的类型不对,如下: 异常代码: $.ajax({ url: api ...

  10. SQL语句中生成UUID方法

    SQL语句中生成UUID方法为UUID() 生成带横线UUID: select UUID()                         形如:abaffaca-fd55-11e5-b3d0-d2 ...