bmi055 标定_Ubuntu16.04+RealsenseT265跑通VINS-Fusion

2023-05-16

一、提前条件

系统版本:ubuntu16.04+ROS(kinetic)

默认已经掌握了ubuntu系统下的基本命令以及ROS的基本操作

二、realsenseT265的SDK测试

官方网站https://www.intelrealsense.com/get-started-tracking-camera/

照着其中https://github.com/IntelRealSense/librealsense/blob/development/doc/distribution_linux.md安装过程进行安装即可,保证运行realsense-viewer后能有相关界面。

三、realsenseT265的标定

1.准备工作(需要注意以下文件编译过程中,可能出现依赖库缺失的报错,这很正常,按照提示的错误信息安装对应依赖库即可)

1.1 下载并编译ceres

git clone https://github.com/ceres-solver/ceres-solver

cd ceres

mkdir build

cd build

cmake ..

make

sudo make install

1.2 下载并编译code_utils

首先,安装依赖库

sudo apt-get install libdw-dev

之后,安装code_utils

cd ~/catkin_ws/src

git clone https://github.com/gaowenliang/code_utils

cd ..

catkin_make

source ~/catkin_ws/devel/setup.bash

如果有报错fatal error: backward.hpp: 没有那个文件或目录。此时在code_utils下面找到sumpixel_test.cpp,修改#include "backward.hpp"为#include “code_utils/backward.hpp”后再catkin_make。

我也遇见过no module named “XXX”的错误,是因为没安装对应的依赖库,安装后再catkin_make即可。

1.3 下载并编译imu_utils

cd ~/catkin_ws/src

git clone https://github.com/gaowenliang/imu_utils.git

cd ..

catkin_make

source ~/catkin_ws/devel/setup.bash

注意:先编译code_utils,再编译imu_utils,不能放在一起编译。

1.4 下载并编译kalibr

首先安装依赖库

sudo apt-get install python-setuptools

sudo apt-get install python-setuptools python-rosinstall ipython libeigen3-dev libboost-all-dev doxygen

sudo apt-get install ros-kinetic-vision-opencv ros-kinetic-image-transport-plugins ros-kinetic-cmake-modules python-software-properties software-properties-common libpoco-dev python-matplotlib python-scipy python-git python-pip ipython libtbb-dev libblas-dev liblapack-dev python-catkin-tools libv4l-dev

接下来安装kalibr

cd ~/catkin_ws/src

git clone https://github.com/ethz-asl/Kalibr.git

cd ..

catkin_make

source ~/catkin_ws/devel/setup.bash

在看其他博客时发现可能会出现python相关的问题,我用的是ubuntu16.04自带的Python 2.7.12版本,在安装过程中没有出现问题。

1.5 下载并安装realsense-ros

首先安装依赖库

sudo apt-get install ros-kinetic-ddynamic-reconfigure

接下来安装realsense-ros

cd ~/catkin_ws/src

git clone https://github.com/IntelRealSense/realsense-ros

cd ~/catkin_ws

catkin_make

source ~/catkin_ws/devel/setup.bash

至此,我们的准备工作就做好了。

2.标定流程

2.1修改工作空间下文件的读写权限,不然后面在运行时会报错

cd ~/catkin_ws

sudo chmod 777 src/ -R

2.2 相关文件的修改

打开位于realsense-ros/realsense2_camera/launch目录下的rs_t265.launch文件,将原本的代码修改为。

在~/catkin_ws/src/imu_utils/launch中新建t265_imu.launch如下

2.3 IMU的校准

将realsenseT265插上电脑后,建议在你喜欢的地方新建一个文件夹,比如我是在桌面上新建了一个文件夹,然后在其中打开终端,输入以下命令

roslaunch realsense2_camera rs_t265.launch

roslaunch imu_utils t265_imu.launch

注意过程中显示wait for imu data是正常情况,等待大约60分钟即可出结果,在你新建的文件夹内生成了BMI055_imu_param.yaml文件,该文件给出了加速度计和陀螺仪三轴的noise_density(后缀n)和random_walk(后缀w),同时计算出了平均值,后面IMU+摄像头联合标定的时候需要这些均值。

2.4 相机的标定

下载官方给的april_6x6_80x80cm_A0.pdf或者其它标定文件。打印或者在屏幕显示,测量实际的尺寸后,在你之前新建的文件夹中新建apriltags.yaml,我的文件内容如下:

target_type: 'aprilgrid' #gridtype

tagCols: 6 #number of apriltags

tagRows: 6 #number of apriltags

tagSize: 0.16 #size of apriltag, edge to edge [m]

tagSpacing: 0.3125 #ratio of space between tags to tagSize

#example: tagSize=2m, spacing=0.5m --> tagSpacing=0.25[-]

之后,在你新建的文件夹中打开终端,开启realsenseT265

roslaunch realsense2_camera rs_t265.launch

修改话题发布频率

rosrun topic_tools throttle messages /camera/fisheye1/image_raw 10.0 /fisheye1

rosrun topic_tools throttle messages /camera/fisheye2/image_raw 10.0 /fisheye2

录制文件,注意录制过程中要缓慢移动相机,使其能看到完整清晰的标定文件(可以先在录制前打开rviz,调用image的话题进行观察,判断移动的位置)

rosbag record -O cameras_calibration /fisheye1 /fisheye2

调用kalibr的算法计算各个摄像头的内参和外参

kalibr_calibrate_cameras --target ./apriltags.yaml --bag ./cameras_calibration.bag --bag-from-to 2 35 --models omni-radtan omni-radtan --topics /fisheye1 /fisheye2

因为并不一定要用整个录制视频,2和35是你想要的起始和截止时间,可以修改。

如果在过程中出现Using the default setup in the initial run leads to an error of Cameras are not connected through mutual observations, please check the dataset. Maybe adjust the approx. sync. tolerance.相机不同步的报错,可以通过修改话题发布的频率,或者在kalibr命令的末尾加上–approx-sync 0.04来解决。

最终会生成camchain-.cameras_calibration.yaml、results-cam-.cameras_calibration.txt和report-cam-.cameras_calibration.pdf。

2.5. Camera-IMU联合标定

在你之前新建的文件夹中,新建imu.yaml文件如下(根据你之前的BMI055_imu_param.yaml填写参数):

#Accelerometers

accelerometer_noise_density: 8.003e-02 #Noise density (continuous-time)

accelerometer_random_walk: 5.382e-03 #Bias random walk

#Gyroscopes

gyroscope_noise_density: 8.163e-03 #Noise density (continuous-time)

gyroscope_random_walk: 3.470e-05 #Bias random walk

rostopic: /imu #the IMU ROS topic

update_rate: 200.0 #Hz (for discretization of the values above)

修改rs_t265.launch其中的两行代码如下:

进入你之前新建的文件夹,打开终端,开启T265

roslaunch realsense2_camera rs_t265.launch

修改发布频率

rosrun topic_tools throttle messages /camera/fisheye1/image_raw 20.0 /fisheye1

rosrun topic_tools throttle messages /camera/fisheye2/image_raw 20.0 /fisheye2

rosrun topic_tools throttle messages /camera/imu 200.0 /imu

录制文件

rosbag record -O imu_cameras_calibration /fisheye1 /fisheye2 /imu

调用kalibr的算法计算IMU和camera外参

kalibr_calibrate_imu_camera --target ./apriltags.yaml --cam ./camchain-.cameras_calibration.yaml --imu ./imu.yaml --bag ./imu_cameras_calibration.bag --bag-from-to 2 35 --max-iter 30 --show-extraction

最终会输出camchain-imucam-.imu_cameras_calibration.yaml、imu-.imu_cameras_calibration.yaml、results-imucam-.imu_cameras_calibration.txt、report-imucam-.imu_cameras_calibration.pdf四个文件,你可以通过pdf文件查看你标定的准确性。

至此,我们完成了相机和IMU的标定。

四、运行VINS-FUSION

先下载并编译VINS-Fusion

cd ~/catkin_ws/src

git clone https://github.com/HKUST-Aerial-Robotics/VINS-Fusion

cd ..

catkin_make

source ~/catkin_ws/devel/setup.bash

在VINS-Fusion/config文件夹中,新建文件夹名为realsense_t265,并在其中新建fisheye1.yaml,fisheye2.yaml,stereo_imu.yaml三个文档,内容如下(注意相关参数需要参考BMI055_imu_param.yaml、results-cam-.cameras_calibration.txt和results-imucam-.imu_cameras_calibration.txt自行修改):

fisheye1.yaml

%YAML:1.0

---

model_type: MEI

camera_name: camera

image_width: 848

image_height: 800

mirror_parameters:

xi: 1.75347951

distortion_parameters:

k1: 0.03509054

k2: -0.3590536

p1: 0.00250588

p2: 0.00058101

projection_parameters:

gamma1: 788.10829678

gamma2: 788.19861186

u0: 416.33019648

v0: 404.21771229

fisheye2.yaml

%YAML:1.0

---

model_type: MEI

camera_name: camera

image_width: 848

image_height: 800

mirror_parameters:

xi: 1.95209328

distortion_parameters:

k1: 0.18993538

k2: -0.8234989

p1: 0.00337246

p2: 0.00013959

projection_parameters:

gamma1: 843.77832442

gamma2: 843.19711184

u0: 419.54774026

v0: 406.36245572

stereo_imu.yaml

%YAML:1.0

#common parameters

#support: 1 imu 1 cam; 1 imu 2 cam: 2 cam;

imu: 1

num_of_cam: 2

imu_topic: "/camera/imu"

image0_topic: "/camera/fisheye1/image_raw"

image1_topic: "/camera/fisheye2/image_raw"

output_path: "~/output"

cam0_calib: "fisheye1.yaml"

cam1_calib: "fisheye2.yaml"

image_width: 848

image_height: 800

# Extrinsic parameter between IMU and Camera.

estimate_extrinsic: 1 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.

# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.

body_T_cam0: !!opencv-matrix #cam0 coordinate under body coordinate

rows: 4

cols: 4

dt: d

data: [-0.9999306582373404, 0.001093290620038494, 0.01172533294445286, 0.5201790241280906,

-0.0011878229478030982, -0.9999668259020238, -0.008058298336212454, 0.04796159845159734,

0.011716133905124508, -0.008071667179143842, 0.9998987850754022, -0.05434762530417168,

0., 0., 0., 1.]

body_T_cam1: !!opencv-matrix

rows: 4

cols: 4

dt: d

data: [-0.9999985320918137, 0.0011840662046389947, -0.0012384673758261621, -0.10570692194161202,

-0.001173065649638605, -0.999960187777609, -0.008845720815767944, 0.048863128512499784,

-0.0012488919887611945, -0.008844255027525165, 0.9999601089152549, -0.04892047362600982,

0., 0., 0., 1. ]

#Multiple thread support

multiple_thread: 1

#feature traker paprameters

max_cnt: 150 # max feature number in feature tracking

min_dist: 30 # min distance between two features

freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image

F_threshold: 1.0 # ransac threshold (pixel)

show_track: 1 # publish tracking image as topic

flow_back: 1 # perform forward and backward optical flow to improve feature tracking accuracy

#optimization parameters

max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time

max_num_iterations: 8 # max solver itrations, to guarantee real time

keyframe_parallax: 10.0 # keyframe selection threshold (pixel)

#imu parameters The more accurate parameters you provide, the better performance

acc_n: 8.00274e-02 # accelerometer measurement noise standard deviation. #0.2 0.04

gyr_n: 8.16326e-03 # gyroscope measurement noise standard deviation. #0.05 0.004

acc_w: 5.38231e-03 # accelerometer bias random work noise standard deviation. #0.002

gyr_w: 3.470378e-05 # gyroscope bias random work noise standard deviation. #4.0e-5

g_norm: 9.805 # gravity magnitude

#unsynchronization parameters

estimate_td: 0 # online estimate time offset between camera and imu

td: 0.0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)

#loop closure parameters

load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'

pose_graph_save_path: "~/output" # save and load path

save_image: 1 # save image in pose graph for visualization prupose; you can close this function by setting 0

之后打开终端,运行

roslaunch realsense2_camera rs_t265.launch

rosrun vins vins_node ~/catkin_ws/src/VINS-Fusion/config/realsense_t265/stereo_imu.yaml

roslaunch vins vins_rviz.launch

就可以开始愉快的跑VINS-Fusion了。

参考文章:

Realsense T265标定及运行VINS–kalibr和imu_utils

如何用Realsense D435i运行VINS-Mono等VIO算法 获取IMU同步数据

使用imu_utils工具生成IMU的Allan方差标定曲线

VINS-Fusion

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

bmi055 标定_Ubuntu16.04+RealsenseT265跑通VINS-Fusion 的相关文章

  • realsense435i运行vins-mono,标定部分

    相机标定 1 安装kalibr xff1b 参考 xff1a https blog csdn net wangbaodong070411209 article details 112248834 https blog csdn net we
  • vins中imu融合_VINS代码解读

    VINS estimator 摘抄 我们初始化的原因是单目惯性紧耦合系统是一个非线性程度很高的系统 xff0c 首先单目是无法获得空间中的绝对尺度 xff0c 而IMU又必然存在偏置 xff0c 在后面进行求解的时候还需要用到重力加速度 包
  • Ubuntu16.04安裝ROS

    此文章在前人的基礎上 xff0c 並把安裝遇到的問題寫出來 Ubuntu16 04安装ROS Kinetic详细过程 https blog csdn net weixin 43159148 article details 83375218
  • VINS-Mono代码学习记录(四)---estimator_node

    写在前面的话 终于把feature tracker这一个node给整理好了 xff0c 那些都是之前就已经看过的内容 xff0c 所以整理起来比较快 xff0c 接下来就慢慢边学边整理吧 xff0c 这次先来看estimator node
  • 【ubuntu16.04 LTS】更换国内清华源

    目录 1 xff0c 备份原始源文件sources list2 xff0c 修改源文件sources list3 xff0c 更新源 1 xff0c 备份原始源文件sources list 在终端输入如下命令 xff1a span clas
  • ubuntu16.04中进行ROS通信编程

    ROS通信学习 基础知识学习字段ROS通信小例子一 创建一个工作区二 创建一个ROS工程包三 创建通信的发 收节点四 测试程序的正确性 图像ROS通信小例子视频ROS通信小例子多机ROS通信 基础知识学习 x1f31f 话题与服务的区别 话
  • Ubuntu 18.04 运行PL-VINS

    代码地址 https span class token operator span span class token comment github com cnqiangfu PL VINS span 安装过程出错参考 PL VINS配置
  • 关于VINS-MONO与VIO轨迹漂移问题定位的一些方向

    整个VINS MONO系统 xff0c 较容易在系统静止或外力给予较大冲击时产生轨迹漂移 xff0c 原因是imu的bias在预积分中持续发散 xff0c 视觉重投影误差产生的约束失效 如静止 xff0c 先验约束可能会在LM的线性求解器中
  • Ubuntu16.04上安装百度网盘后打不开

    现在百度网盘推出了Linux版本 xff0c 也有Ubuntu下安装的deb文件 xff0c 但是我在Ubuntu上安装后却打不开 xff0c 报错 baidunetdisk crashed with SIGABRT in gnu cxx
  • 在ubuntu20.04上配置VINS_Fusion(亲测有效,一应俱全)

    最近在做科研训练的时候配置了HKUST Aerial Robotics实验室的VINS Fusion代码项目 xff0c 经历了一些编译报错的问题 xff0c 在网上查找的时候博客内容良莠不齐 xff0c 且实质针对性意见不多 xff0c
  • Ubuntu16.04下的FireFox浏览器无法查看网页视频的原因及解决方法

    Ubuntu16 04自带的firefox浏览器 在搭建好其他环境后 xff0c 我通过firefox去廖雪峰老师的官网查看python的教程 xff0c 发现无法打开网页中的视频 此时 xff0c 我又通过firefox浏览器中进入了腾讯
  • 在TUMVI数据集上测试VINS-Fusion算法

    VINS Fusion算法是一个非常优秀的视觉惯性里程计 但原版VINS Fusion并没有提供与TUM数据集相应的配置文件 因此需要自己进行写yaml文件 修改配置文件 tum mono yaml span class token dir
  • RealSenseD435i (四):运行 VINS-mono代码

    一 必读博客 nbsp https blog csdn net hltt3838 article details 120691764 nbsp nbsp nbsp 一 https blog csdn net hltt3838 article
  • vins中的坐标系变换及g2r函数

    slam中经常会需要表示一个刚体的位姿 例如imu的位姿 xff0c 相机的位姿 首先我们需要在一个刚体上架上一个坐标系 这个坐标系为本体坐标系 怎么架一个坐标系 xff1f imu本身就有规定其本身的x y z轴的方向 相机一般认为 xf
  • VINS-Mono代码阅读笔记(十三):posegraph中四自由度位姿优化

    本篇笔记紧接着VINS Mono代码阅读笔记 xff08 十二 xff09 xff1a 将关键帧加入位姿图当中 xff0c 来学习pose graph当中的紧耦合优化部分 在重定位完成之后 xff0c 进行位姿图优化是为了将已经产生的所有位
  • Cmake升级 更新 Ubuntu16.04 + ROS

    重要提示 千万不要卸载 Ubuntu原有的cmake xff0c 否则之前经过原有cmake编译过的文件将也会被删除 xff0c 比如 ros 千万不要使用下面这句命令删除原有的 cmake xff01 xff01 xff01 xff01
  • 【VINS论文翻译】VINS-Mono: A Robust and Versatile Monocular Visual-Inertial State Estimator

    回到目录 写在前面 港科大的VINS Mono作为目前state of the art的开源VIO项目 xff0c 是研究视觉与IMU紧耦合的必读算法 xff0c 网上的论文解读与代码实现也非常丰富 xff08 感谢 xff01 xff09
  • VMware Fusion 挂载物理机硬盘(整盘)

    以下操作前提 系统为 Mac OS OSX 安装了 VMware Fusion 实现原理 类似ESXI中的RDM映射 将物理硬盘映射到一个VM虚拟磁盘 可供VM选择的虚拟磁盘文件 首先查询本机硬盘情况 diskutil list 采用SCS
  • 2021-08-06

    在编译OKVIS中 执行make j8时报错的解决方法 1 根据github上OKVIS的安装步骤一步一步执行 由于github经常进不去 我就进了gitee网站查到OKVIS的安装步骤 参考链接 https gitee com bill4
  • Fusion Log Viewer 的替代品?

    除了 Fuslogvw exe 之外 是否还有其他 Fusion 日志查看器程序 或者将 Fusion 日志输出定向到您自己的目录 然后手动检查大量 HTM 文件 我的两个主要抱怨是 我想要一个概述 显示哪些程序集加载成功 哪些失败 我不确

随机推荐