记录手持多传感器融合设备标定全过程

设备位置经过调整,再次进行标定,这次记录过程

设备如图:

标定板如图:

相机和IMU内参已通过之前标定得到

cam0:
  cam_overlaps: []
  camera_model: pinhole
  distortion_coeffs: [0.09686982946027908, -0.22080021822510262, 0.000986198221581305, -0.0005036817735604531]
  distortion_model: radtan
  intrinsics: [894.4294891835768, 894.4119327837665, 631.1430468218376, 374.2690814294581]
  resolution: [1280, 720]
  rostopic: /camera/color/image_raw
%YAML:1.0
---
type: IMU
name: IG1
Gyr:
   unit: " rad/s"
   avg-axis:
      gyr_n: 2.1878495896798930e-04
      gyr_w: 3.3415939258511154e-06
   x-axis:
      gyr_n: 2.3262429882317745e-04
      gyr_w: 5.3676222885673781e-07
   y-axis:
      gyr_n: 2.0133213043081575e-04
      gyr_w: 4.6488465334196942e-06
   z-axis:
      gyr_n: 2.2239844764997471e-04
      gyr_w: 4.8391730152769148e-06
Acc:
   unit: " m/s^2"
   avg-axis:
      acc_n: 1.4824723551607947e-02
      acc_w: 1.5915028432955352e-04
   x-axis:
      acc_n: 1.5190470016408220e-02
      acc_w: 1.9008071681021714e-04
   y-axis:
      acc_n: 1.4845893984708746e-02
      acc_w: 1.6498113136916614e-04
   z-axis:
      acc_n: 1.4437806653706876e-02
      acc_w: 1.2238900480927723e-04

一、相机内参标定

项目主要使用到相机的彩色图像,因此只对单目进行标定,由于之前做过,这次直接用以前的结果,有时间补档

二、imu内参的标定

同上

三、相机与IMU外参的标定

使用kalibr工具:

GitHub - ethz-asl/kalibr: The Kalibr visual-inertial calibration toolboxThe Kalibr visual-inertial calibration toolbox. Contribute to ethz-asl/kalibr development by creating an account on GitHub.icon-default.png?t=N7T8https://github.com/ethz-asl/kalibr

录制BAG:

rosbag record -O bd /camera/color/image_raw /imu/data

开始标定:

cd  ~/calib/kalibr_workspace

source devel/setup.bash

rosrun kalibr kalibr_calibrate_imu_camera --target '/home/lb/calib/kalibr_workspace/april_6x6.yaml' --bag '/media/lb/liubo/bd.bag' --bag-from-to 3 50 --cam '/home/lb/download/bd_resurt/camera_1280_720-results.yaml'  --imu '/home/lb/download/bd_resurt/imu.yaml' --show-extraction

下面我对各项进行一下解释 :

rosrun kalibr kalibr_calibrate_imu_camera

  • rosrun:这是ROS中用于运行特定包及其节点的命令行工具。

  • kalibr_calibrate_imu_camera:这是ROS包的名称和该包中的特定节点或可执行文件的名称。它用于校准IMU和相机之间的内部和外部参数。

--target '/home/lb/calib/kalibr_workspace/april_6x6.yaml'

--target:指定校准目标,这里是一个棋盘格模式。YAML文件(april_6x6.yaml)可能包含有关目标的信息,如棋盘格的大小。

--bag '/media/lb/liubo/bd.bag' --bag-from-to 3 50

  • --bag:指定包含记录的传感器数据的ROS bag文件。Bag文件(bd.bag)是ROS中用于存储传感器数据的一种格式。

  • --bag-from-to 3 50:指定要从bag文件中使用的消息范围。在这种情况下,它从消息索引3到50提取数据。

--cam '/home/lb/download/bd_resurt/camera_1280_720-results.yaml'

--cam:指定相机校准文件。YAML文件(camera_1280_720-results.yaml)包含有关相机内部参数的信息

--imu '/home/lb/download/bd_resurt/imu.yaml'

--imu:指定IMU校准文件。YAML文件(imu.yaml)包含有关IMU参数的信息。

--show-extraction

此标志表示将在校准过程中显示或可视化提取过程。

出现的报错:

报错:ImportError: No module named scipy.optimize

解决方法:sudo apt-get install python-scipy

耐心等待结果,时间因电脑而异,2min-30min, 完成后会在标定使用BAG的同级目录下生成以下文件

由此即可得到标定结果

四、imu和lidar外参的标定

使用浙大开源的方案

GitHub - APRIL-ZJU/lidar_IMU_calib: Targetless Calibration of LiDAR-IMU System Based on Continuous-time Batch EstimationTargetless Calibration of LiDAR-IMU System Based on Continuous-time Batch Estimation - GitHub - APRIL-ZJU/lidar_IMU_calib: Targetless Calibration of LiDAR-IMU System Based on Continuous-time Batch Estimationicon-default.png?t=N7T8https://github.com/APRIL-ZJU/lidar_IMU_calib

 录制BAG:

rosbag record -O li  /imu/data  /velodyne_packets

这里有一些注意事项:

1、录制的雷达话题是/velodyne_packets,格式是velodyne_msgs/VelodyneScan而不是sensor_msgs/PointCloud2格式,如果录制错了也不用急,这两种格式可以转换,当然重现录制可能更方便一点。

2、录制时要有充分的移动,最好在室内,尽可能减少录制玻璃等物体

开始标定:

首先更改配置文件:

/home/lb/calib/catkin_zd/src/lidar_IMU_calib/launch/licalib_gui.launch

<?xml version="1.0"?>
<launch>
    <arg name="topic_imu"           default="/imu/data" />
    <arg name="path_bag"            default="/home/lb/桌面/li.bag" />
    <arg name="bag_start"           default="1" />
    <arg name="bag_durr"            default="40" />
    <arg name="scan4map"            default="15" />
    <arg name="lidar_model"         default="VLP_16" />
    <arg name="ndtResolution"       default="0.5" /> <!-- 0.5 for indoor case and 1.0 for outdoor case -->

    <arg name="time_offset_padding" default="0.015" />
    <arg name="show_ui"    default="true" />

    <node pkg="li_calib" type="li_calib_gui" name="li_calib_gui" output="screen">
    <!-- <node pkg="li_calib" type="li_calib_gui" name="li_calib_gui" output="screen" clear_params="true" launch-prefix="gdb -ex run &#45;&#45;args">-->

        <param name="topic_imu"         type="string"   value="$(arg topic_imu)" />
        <param name="topic_lidar"       type="string"   value="/velodyne_packets" />
        <param name="LidarModel"        type="string"   value="$(arg lidar_model)" />
        <param name="path_bag"          type="string"   value="$(arg path_bag)" />
        <param name="bag_start"         type="double"   value="$(arg bag_start)" />
        <param name="bag_durr"          type="double"   value="$(arg bag_durr)" /> <!-- for data association -->
        <param name="scan4map"          type="double"   value="$(arg scan4map)" />
        <param name="ndtResolution"     type="double"   value="$(arg ndtResolution)" />

        <param name="time_offset_padding"   type="double"   value="$(arg time_offset_padding)" />
        <param name="show_ui"               type="bool"     value="$(arg show_ui)" />
    </node>

</launch>

这里的只要修改就是imu的topic 、BAG的位置和开始和结束的时间,如果是velodyne16线激光雷达其他的不用修改,不是的话,需要对源码进行一定的修改进行适配,有人做过这方面的工作,有需求的可以多多百度。

然后运行launch文件即可

cd ~/calib/catkin_zd
source devel/setup.bash
roslaunch li_calib licalib_gui.launch 

 出现UI界面后按顺序点击初始化、数据关联、匹配优化、数据精炼就是如下

 

可以重复点多迭代几次,数据会发生微调,然后保存地图就会保存结果和PCD,但是没有太大必要,可以直接在终端看到结果:

P_LinI      :  0.0585905  -0.102107 -0.0492073
euler_LtoI  : 0.314218   0.1246 -177.198
P_IinL      : 0.0536213 -0.105123 0.0485191
euler_ItoL  : 0.319934 0.109089  177.197
time offset : 0
gravity     : -0.635769   9.29983   2.99215
acce bias   :   -0.088798   0.0470856 -0.00584321
gyro bias   : -1.58483e-06  -0.00231211  0.000299033

这里是欧拉角,L代表lidar,  I代表imu 可以简单使用如下py脚本转化为旋转矩阵

#coding:utf-8
import numpy as np

def euler_to_rotation_matrix(roll, pitch, yaw):
    # 将欧拉角转换为弧度
    roll = np.radians(roll)
    pitch = np.radians(pitch)
    yaw = np.radians(yaw)

    # 计算旋转矩阵的元素
    cos_roll = np.cos(roll)
    sin_roll = np.sin(roll)
    cos_pitch = np.cos(pitch)
    sin_pitch = np.sin(pitch)
    cos_yaw = np.cos(yaw)
    sin_yaw = np.sin(yaw)

    # 构建旋转矩阵
    rotation_matrix = np.array([
        [cos_pitch * cos_yaw, cos_yaw * sin_pitch * sin_roll - cos_roll * sin_yaw, cos_roll * cos_yaw * sin_pitch + sin_roll * sin_yaw],
        [cos_pitch * sin_yaw, cos_roll * cos_yaw + sin_pitch * sin_roll * sin_yaw, -cos_yaw * sin_roll + cos_roll * sin_pitch * sin_yaw],
        [-sin_pitch, cos_pitch * sin_roll, cos_pitch * cos_roll]
    ])

    return rotation_matrix

# 示例使用
roll =  0.314218  # 沿着 x 轴旋转的角度
pitch = 0.1246  # 沿着 y 轴旋转的角度
yaw =  -177.198  # 沿着 z 轴旋转的角度

rotation_matrix = euler_to_rotation_matrix(roll, pitch, yaw)
print(rotation_matrix)

五、camera和lidar外参标定

我们已经有了lidar和imu的,和camera和IMU的外参,两者相乘即可,也可以使用AUTOware里的功能包进行标定,用作验证

GitHub - XidianLemon/calibration_camera_lidar: 从autoware分离出来的相机雷达联合标定ros包从autoware分离出来的相机雷达联合标定ros包. Contribute to XidianLemon/calibration_camera_lidar development by creating an account on GitHub.icon-default.png?t=N7T8https://github.com/XidianLemon/calibration_camera_lidar这个安装稍显麻烦,可参考:

calibration_toolkit,雷达相机标定工具安装-CSDN博客文章浏览阅读352次。标定工具箱安装教程参考:https://github.com/XidianLemon/calibration_camera_lidar,把工程克隆到自己本地工程的src目录下编译即可。六、/calibration_camera_lidar-master/ls_calibration/calibration_camera_lidar下的CMakeLists.txt中。三、scan_window.cpp与camera_lidar2d_offline_calib.cpp中CV-RGB改为cvScalar。_相机标定工具https://blog.csdn.net/weixin_44760904/article/details/131870458?spm=1001.2014.3001.5502 同相机和IMU的内参,此次没有用到,有时间补档

最后,如果有人向进一步咨询也可以联系本人,可以根据情况提供一些技术支持

  • 3
    点赞
  • 1
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

水理璇浮

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值