保姆级避坑指南:在Ubuntu 20.04上搞定Realsense D435i的IMU与相机联合标定(含Kalibr常见报错解决)
保姆级避坑指南Ubuntu 20.04下Realsense D435i的IMU与相机联合标定全流程当你在机器人或计算机视觉项目中首次尝试使用Intel Realsense D435i进行IMU和相机的联合标定时可能会遇到各种令人沮丧的问题。从环境配置到标定执行每一步都可能隐藏着意想不到的坑。本文将带你完整走一遍这个流程并重点解决那些最容易导致失败的环节。1. 环境准备避开依赖地狱在开始标定之前正确的环境配置是成功的一半。Ubuntu 20.04虽然稳定但软件包版本间的兼容性问题可能让你寸步难行。1.1 ROS Noetic基础环境首先确保你的ROS Noetic安装完整sudo apt install ros-noetic-desktop-full echo source /opt/ros/noetic/setup.bash ~/.bashrc source ~/.bashrc常见问题1如果你之前安装过其他ROS版本务必彻底清理旧版本避免冲突。使用locate ros查找并删除所有相关文件。1.2 Realsense驱动安装官方推荐的安装方式有时会遇到内核模块编译问题sudo apt-key adv --keyserver keys.gnupg.net --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE || sudo apt-key adv --keyserver hkp://keyserver.ubuntu.com:80 --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE sudo add-apt-repository deb https://librealsense.intel.com/Debian/apt-repo $(lsb_release -cs) main -u sudo apt-get install librealsense2-dkms librealsense2-utils librealsense2-dev librealsense2-dbg安装后验证realsense-viewer避坑提示如果设备未被识别尝试sudo apt install linux-headers-$(uname -r)遇到权限问题创建udev规则echo SUBSYSTEMusb, ATTR{idVendor}8086, MODE0666 | sudo tee /etc/udev/rules.d/99-realsense.rules sudo udevadm control --reload-rules sudo udevadm trigger2. IMU单独标定从源码编译到数据采集IMU标定是联合标定的基础但imu_utils的编译过程可能是第一个拦路虎。2.1 编译code_utils和imu_utils创建工作空间mkdir -p ~/imu_calib_ws/src cd ~/imu_calib_ws/src git clone https://github.com/gaowenliang/code_utils.git git clone https://github.com/gaowenliang/imu_utils.git关键修改1所有CMakeLists.txt中的C标准改为14set(CMAKE_CXX_FLAGS -stdc14)关键修改2对于OpenCV 4.x用户必须执行cd ~/imu_calib_ws/src/code_utils sed -i s/CV_LOAD_IMAGE_UNCHANGED/cv::IMREAD_UNCHANGED/g grep CV_LOAD_IMAGE_UNCHANGED -rl ./ sed -i s/CV_LOAD_IMAGE_GRAYSCALE/cv::IMREAD_GRAYSCALE/g grep CV_LOAD_IMAGE_GRAYSCALE -rl ./安装依赖sudo apt install libdw-dev编译cd ~/imu_calib_ws catkin_make致命错误解决如果遇到backward.hpp找不到修改包含路径为#include code_utils/backward.hpp2.2 IMU数据采集与标定创建采集目录mkdir -p ~/imu_calib_ws/bag启动Realsense发布IMU数据roslaunch realsense2_camera rs_camera.launch录制静态数据至少2小时rosbag record /camera/imu -O ~/imu_calib_ws/bag/imu.bag创建启动文件d435i.launchlaunch node pkgimu_utils typeimu_an nameimu_an outputscreen param nameimu_topic typestring value/camera/imu/ param nameimu_name typestring valued435i/ param namedata_save_path typestring value$(find imu_utils)/../../bag// param namemax_time_min typeint value120/ param namemax_cluster typeint value400/ /node /launch开始标定roslaunch imu_utils d435i.launch rosbag play -r 200 ~/imu_calib_ws/bag/imu.bag结果验证检查生成的d435i_imu_param.yaml应有合理的噪声参数accelerometer_noise_density: 2.37e-02 # 连续时间噪声密度 accelerometer_random_walk: 3.50e-04 # 随机游走 gyroscope_noise_density: 2.92e-03 # 陀螺仪噪声密度 gyroscope_random_walk: 2.03e-05 # 陀螺仪随机游走3. 相机标定Kalibr的正确打开方式相机标定是联合标定的另一基础Kalibr工具的使用需要特别注意版本兼容性。3.1 Kalibr安装与配置创建工作空间mkdir -p ~/kalibr_ws/src cd ~/kalibr_ws/src git clone https://github.com/ethz-asl/kalibr.git安装依赖sudo apt install python3-dev python3-pip python3-scipy python3-matplotlib sudo apt install python3-tk python3-pyqt5 python3-opencv pip3 install numpy1.21.0 pyyaml rospkg pandas版本陷阱必须使用numpy 1.21否则会遇到AttributeError: module numpy has no attribute typeDict错误。编译Kalibrcd ~/kalibr_ws catkin build -DCMAKE_BUILD_TYPERelease -j43.2 标定板准备生成AprilTag标定板rosrun kalibr kalibr_create_target_pdf --type apriltag --nx 6 --ny 6 --tsize 0.022 --tspace 0.3关键步骤必须实际测量打印后标定板的物理尺寸创建april_6x6.yamltarget_type: aprilgrid tagCols: 6 tagRows: 6 tagSize: 0.0318 # 实际测量值(m) tagSpacing: 0.305 # tagSize比例3.3 双目相机数据采集降低图像发布频率至4Hzrosrun topic_tools throttle messages /camera/infra1/image_rect_raw 4.0 /infra_left rosrun topic_tools throttle messages /camera/infra2/image_rect_raw 4.0 /infra_right录制数据rosbag record /infra_left /infra_right -O ~/kalibr_ws/bag/stereo.bag采集技巧缓慢移动相机确保标定板始终在视野内包含各种旋转和平移运动持续时间90秒以上运动轨迹建议先平移后旋转3.4 执行相机标定rosrun kalibr kalibr_calibrate_cameras \ --target ~/kalibr_ws/bag/april_6x6.yaml \ --bag ~/kalibr_ws/bag/stereo.bag \ --models pinhole-radtan pinhole-radtan \ --topics /infra_left /infra_right \ --bag-from-to 10 130 \ --show-extraction \ --approx-sync 0.04常见错误解决初始焦距失败export KALIBR_MANUAL_FOCAL_LENGTH_INIT1当提示时输入合理值如400相机不同步 调整--approx-sync参数从0.1逐步减小numpy.float错误 修改CameraUtils.pymean np.mean(rerr_matrix, 0, dtypenp.float64) std np.std(rerr_matrix, 0, dtypenp.float64)4. 联合标定IMU与相机的时空对齐联合标定是最后也是最关键的一步需要整合前两步的结果。4.1 准备配置文件创建imu.yaml基于IMU标定结果accelerometer_noise_density: 2.37e-02 accelerometer_random_walk: 3.50e-04 gyroscope_noise_density: 2.92e-03 gyroscope_random_walk: 2.03e-05 rostopic: /imu update_rate: 200.0创建stereo.yaml基于相机标定结果cam0: camera_model: pinhole distortion_coeffs: [0.0082, -0.0043, 0.0002, 0.0008] distortion_model: radtan intrinsics: [382.67, 382.92, 322.76, 236.70] resolution: [640, 480] rostopic: /infra_left cam1: camera_model: pinhole distortion_coeffs: [0.0086, -0.0051, -0.0002, 0.0004] distortion_model: radtan intrinsics: [382.64, 382.87, 322.37, 236.65] resolution: [640, 480] rostopic: /infra_right4.2 联合数据采集调整话题频率rosrun topic_tools throttle messages /camera/infra1/image_rect_raw 4.0 /infra_left rosrun topic_tools throttle messages /camera/infra2/image_rect_raw 4.0 /infra_right rosrun topic_tools throttle messages /camera/imu 200.0 /imu录制数据rosbag record /infra_left /infra_right /imu -O ~/kalibr_ws/bag/stereo_imu.bag运动技巧先静止10秒让IMU初始化缓慢进行6自由度运动确保标定板在大部分帧中可见总时长控制在50-60秒4.3 执行联合标定rosrun kalibr kalibr_calibrate_imu_camera \ --target ~/kalibr_ws/bag/april_6x6.yaml \ --bag ~/kalibr_ws/bag/stereo_imu.bag \ --cam ~/kalibr_ws/bag/stereo.yaml \ --imu ~/kalibr_ws/bag/imu.yaml \ --bag-from-to 10 60 \ --show-extraction结果验证 检查输出的变换矩阵和时间偏移是否合理T_ci: (imu0 to cam0): [[ 0.99991885 -0.00448156 -0.01192529 -0.00263335] [ 0.00454447 0.99997587 0.00525384 -0.00174852] [ 0.01190145 -0.00530761 0.99991509 -0.00021396] [ 0. 0. 0. 1. ]] timeshift cam0 to imu0: 0.00227887 [s]性能指标重投影误差应0.15像素IMU误差应0.01 rad/s(陀螺)和0.1 m/s²(加速度计)时间偏移通常为几毫秒