国产 无码 综合区,色欲AV无码国产永久播放,无码天堂亚洲国产AV,国产日韩欧美女同一区二区

Ubuntu 20.04 Intel RealSense D435i 相機(jī)標(biāo)定教程

這篇具有很好參考價(jià)值的文章主要介紹了Ubuntu 20.04 Intel RealSense D435i 相機(jī)標(biāo)定教程。希望對(duì)大家有所幫助。如果存在錯(cuò)誤或未考慮完全的地方,請(qǐng)大家不吝賜教,您也可以點(diǎn)擊"舉報(bào)違法"按鈕提交疑問。

下載編譯code_utils

mkdir -p ~/imu_catkin_ws/src
cd ~/imu_catkin_ws/src
catkin_init_workspace
source ~/imu_catkin_ws/devel/setup.bash
git clone https://github.com/gaowenliang/code_utils.git
cd ..
catkin_make

報(bào)錯(cuò):sumpixel_test.cpp:2:10: fatal error: backward.hpp: 沒有那個(gè)文件或目錄,將sumpixel_test.cpp中# include "backward.hpp"改為:#include “code_utils/backward.hpp”。
報(bào)錯(cuò)

修改成: cv::IMREAD_UNCHANGED
Mat img1 = imread( "/home/gao/IMG_1.png",  cv::IMREAD_UNCHANGED );
sudo apt-get install libdw-dev
添加
#include <opencv2/opencv.hpp>
#include <time.h>

下載編譯imu_utils

cd ~/imu_catkin_ws/src/
git clone https://github.com/gaowenliang/imu_utils.git
cd ..
catkin_make

安裝kalibr 依賴

sudo apt-get install python3-setuptools
 
sudo apt-get install python3-setuptools python3-rosinstall python3-ipython libeigen3-dev libboost-all-dev doxygen libopencv-dev
 
sudo apt-get install libopencv-dev ros-noetic-vision-opencv ros-noetic-image-transport-plugins ros-noetic-cmake-modules python3-software-properties software-properties-common libpoco-dev python3-matplotlib python3-scipy python3-git python3-pip libtbb-dev libblas-dev liblapack-dev python3-catkin-tools libv4l-dev

sudo pip install python-igraph --upgrade

如果不成功,則可以直接安裝:
 
sudo apt-get install python-igraph

sudo apt-get install python3-pyx

sudo apt-get install python3-wxgtk4.0
sudo apt-get install python3-igraph
sudo apt-get install python3-scipy

mkdir -p ~/kalibr_ws/src
cd ~/kalibr_ws
source /opt/ros/noetic/setup.bash
catkin init
catkin config --extend /opt/ros/noetic
catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release
cd ~/kalibr_ws/src
git clone https://github.com/ethz-asl/Kalibr.git
cd ~/kalibr_ws
catkin build -DCMAKE_BUILD_TYPE=Release -j32

重新打開一個(gè)終端:
echo "source ~/kalibr_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc

IMU標(biāo)定

創(chuàng)建rs_imu_calibration.launch

找到realsense-ros包,進(jìn)入/catkin_ws/src/realsense2_camera/launch(路徑僅供參考),復(fù)制其中的rs_camera.launch,并重命名為rs_imu_calibration.launch(命名隨意),并對(duì)里面的內(nèi)容做如下更改

<arg name="unite_imu_method"          default=""/>
//       ########### 改為#############
<arg name="unite_imu_method"          default="linear_interpolation"/>
<arg name="enable_gyro"         default="false"/>  “false” 改為”true”
<arg name="enable_accel"        default="false"/>   “false” 改為”true”
<launch>
  <arg name="serial_no"           default=""/>
  <arg name="usb_port_id"         default=""/>
  <arg name="device_type"         default=""/>
  <arg name="json_file_path"      default=""/>
  <arg name="camera"              default="camera"/>
  <arg name="tf_prefix"           default="$(arg camera)"/>
  <arg name="external_manager"    default="false"/>
  <arg name="manager"             default="realsense2_camera_manager"/>
  <arg name="output"              default="screen"/>
  <arg name="respawn"              default="false"/>

  <arg name="fisheye_width"       default="-1"/>
  <arg name="fisheye_height"      default="-1"/>
  <arg name="enable_fisheye"      default="false"/>

  <arg name="depth_width"         default="640"/>
  <arg name="depth_height"        default="480"/>
  <arg name="enable_depth"        default="true"/>

  <arg name="confidence_width"    default="-1"/>
  <arg name="confidence_height"   default="-1"/>
  <arg name="enable_confidence"   default="true"/>
  <arg name="confidence_fps"      default="-1"/>

  <arg name="infra_width"         default="640"/>
  <arg name="infra_height"        default="480"/>
  <arg name="enable_infra"        default="true"/>
  <arg name="enable_infra1"       default="true"/>
  <arg name="enable_infra2"       default="true"/>
  <arg name="infra_rgb"           default="false"/>

  <arg name="color_width"         default="640"/>
  <arg name="color_height"        default="480"/>
  <arg name="enable_color"        default="true"/>

  <arg name="fisheye_fps"         default="-1"/>
  <arg name="depth_fps"           default="30"/>
  <arg name="infra_fps"           default="30"/>
  <arg name="color_fps"           default="30"/>
  <arg name="gyro_fps"            default="-1"/>
  <arg name="accel_fps"           default="-1"/>
  <arg name="enable_gyro"         default="true"/>
  <arg name="enable_accel"        default="true"/>

  <arg name="enable_pointcloud"         default="false"/>
  <arg name="pointcloud_texture_stream" default="RS2_STREAM_COLOR"/>
  <arg name="pointcloud_texture_index"  default="0"/>
  <arg name="allow_no_texture_points"   default="false"/>
  <arg name="ordered_pc"                default="false"/>

  <arg name="enable_sync"               default="true"/>
  <arg name="align_depth"               default="true"/>

  <arg name="publish_tf"                default="true"/>
  <arg name="tf_publish_rate"           default="0"/>

  <arg name="filters"                   default=""/>
  <arg name="clip_distance"             default="-2"/>
  <arg name="linear_accel_cov"          default="0.01"/>
  <arg name="initial_reset"             default="false"/>
  <arg name="reconnect_timeout"         default="6.0"/>
  <arg name="wait_for_device_timeout"   default="-1.0"/>
  <arg name="unite_imu_method"          default="linear_interpolation"/>
  <arg name="topic_odom_in"             default="odom_in"/>
  <arg name="calib_odom_file"           default=""/>
  <arg name="publish_odom_tf"           default="true"/>
  <arg name="hold_back_imu_for_frames"  default="true"/>

  <arg name="stereo_module/exposure/1"  default="7500"/>
  <arg name="stereo_module/gain/1"      default="16"/>
  <arg name="stereo_module/exposure/2"  default="1"/>
  <arg name="stereo_module/gain/2"      default="16"/>
  
  

  <group ns="$(arg camera)">
    <include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml">
      <arg name="tf_prefix"                value="$(arg tf_prefix)"/>
      <arg name="external_manager"         value="$(arg external_manager)"/>
      <arg name="manager"                  value="$(arg manager)"/>
      <arg name="output"                   value="$(arg output)"/>
      <arg name="respawn"                  value="$(arg respawn)"/>
      <arg name="serial_no"                value="$(arg serial_no)"/>
      <arg name="usb_port_id"              value="$(arg usb_port_id)"/>
      <arg name="device_type"              value="$(arg device_type)"/>
      <arg name="json_file_path"           value="$(arg json_file_path)"/>

      <arg name="enable_pointcloud"        value="$(arg enable_pointcloud)"/>
      <arg name="pointcloud_texture_stream" value="$(arg pointcloud_texture_stream)"/>
      <arg name="pointcloud_texture_index"  value="$(arg pointcloud_texture_index)"/>
      <arg name="enable_sync"              value="$(arg enable_sync)"/>
      <arg name="align_depth"              value="$(arg align_depth)"/>

      <arg name="fisheye_width"            value="$(arg fisheye_width)"/>
      <arg name="fisheye_height"           value="$(arg fisheye_height)"/>
      <arg name="enable_fisheye"           value="$(arg enable_fisheye)"/>

      <arg name="depth_width"              value="$(arg depth_width)"/>
      <arg name="depth_height"             value="$(arg depth_height)"/>
      <arg name="enable_depth"             value="$(arg enable_depth)"/>

      <arg name="confidence_width"         value="$(arg confidence_width)"/>
      <arg name="confidence_height"        value="$(arg confidence_height)"/>
      <arg name="enable_confidence"        value="$(arg enable_confidence)"/>
      <arg name="confidence_fps"           value="$(arg confidence_fps)"/>

      <arg name="color_width"              value="$(arg color_width)"/>
      <arg name="color_height"             value="$(arg color_height)"/>
      <arg name="enable_color"             value="$(arg enable_color)"/>

      <arg name="infra_width"              value="$(arg infra_width)"/>
      <arg name="infra_height"             value="$(arg infra_height)"/>
      <arg name="enable_infra"             value="$(arg enable_infra)"/>
      <arg name="enable_infra1"            value="$(arg enable_infra1)"/>
      <arg name="enable_infra2"            value="$(arg enable_infra2)"/>
      <arg name="infra_rgb"                value="$(arg infra_rgb)"/>

      <arg name="fisheye_fps"              value="$(arg fisheye_fps)"/>
      <arg name="depth_fps"                value="$(arg depth_fps)"/>
      <arg name="infra_fps"                value="$(arg infra_fps)"/>
      <arg name="color_fps"                value="$(arg color_fps)"/>
      <arg name="gyro_fps"                 value="$(arg gyro_fps)"/>
      <arg name="accel_fps"                value="$(arg accel_fps)"/>
      <arg name="enable_gyro"              value="$(arg enable_gyro)"/>
      <arg name="enable_accel"             value="$(arg enable_accel)"/>

      <arg name="publish_tf"               value="$(arg publish_tf)"/>
      <arg name="tf_publish_rate"          value="$(arg tf_publish_rate)"/>

      <arg name="filters"                  value="$(arg filters)"/>
      <arg name="clip_distance"            value="$(arg clip_distance)"/>
      <arg name="linear_accel_cov"         value="$(arg linear_accel_cov)"/>
      <arg name="initial_reset"            value="$(arg initial_reset)"/>
      <arg name="reconnect_timeout"        value="$(arg reconnect_timeout)"/>
      <arg name="wait_for_device_timeout"  value="$(arg wait_for_device_timeout)"/>
      <arg name="unite_imu_method"         value="$(arg unite_imu_method)"/>
      <arg name="topic_odom_in"            value="$(arg topic_odom_in)"/>
      <arg name="calib_odom_file"          value="$(arg calib_odom_file)"/>
      <arg name="publish_odom_tf"          value="$(arg publish_odom_tf)"/>
      <arg name="stereo_module/exposure/1" value="$(arg stereo_module/exposure/1)"/>
      <arg name="stereo_module/gain/1"     value="$(arg stereo_module/gain/1)"/>
      <arg name="stereo_module/exposure/2" value="$(arg stereo_module/exposure/2)"/>
      <arg name="stereo_module/gain/2"     value="$(arg stereo_module/gain/2)"/>

      <arg name="allow_no_texture_points"  value="$(arg allow_no_texture_points)"/>
      <arg name="ordered_pc"               value="$(arg ordered_pc)"/>
      
    </include>
  </group>
</launch>

將accel和gyro的數(shù)據(jù)合并得到imu話題,如果不這樣做發(fā)布的topic中只有加速度計(jì)和陀螺儀分開的topic,沒有合并的camera/imu 話題。

創(chuàng)建d435i_imu_calibration.launch

在~/imu_catkin_ws/src/imu_utils/launch路徑創(chuàng)建d435i_imu_calibration.launch

cd ~/imu_catkin_ws/src/imu_utils/launch
gedit d435i_imu_calibration.launch
<launch>
    <node pkg="imu_utils" type="imu_an" name="imu_an" output="screen">
    	<!--TOPIC名稱和上面一致-->
        <param name="imu_topic" type="string" value= "/camera/imu"/>
        <!--imu_name 無所謂-->
        <param name="imu_name" type="string" value= "d435i"/>
        <!--標(biāo)定結(jié)果存放路徑-->
        <param name="data_save_path" type="string" value= "$(find imu_utils)/data/"/>
        <!--數(shù)據(jù)錄制時(shí)間-min 120分鐘 可以自行修改 一般要大于60-->
        <param name="max_time_min" type="int" value= "120"/>
        <!--采樣頻率,即是IMU頻率,采樣頻率可以使用rostopic hz /camera/imu查看,設(shè)置為400,為后面的rosbag play播放頻率-->
        <param name="max_cluster" type="int" value= "400"/>
    </node>
</launch>

錄制imu數(shù)據(jù)包

插上相機(jī),realsense靜止放置,放置時(shí)間要稍大于d435i_imu_calibration.launch中的錄制時(shí)間,即大于120分鐘。
roscore 
roslaunch realsense2_camera rs_imu_calibration.launch
cd ~/imu_catkin_ws      //等下錄制到這個(gè)文件夾上
rosbag record -O imu_calibration /camera/imu    // 生成的包名稱imu_calibration.bag

目錄有一個(gè)名為 imu_calibration.bag的文件,其中imu_calibration是bag包的名字,可以更改,/camera/imu是發(fā)布的IMU topic,可以通過以下命令查看。

rostopic list -v

運(yùn)行校準(zhǔn)程序

首先激活imu_util工作空間的setup.bash

source ~/imu_catkin_ws/devel/setup.bash
roslaunch imu_utils d435i_imu_calibration.launch

回放數(shù)據(jù)包

  打開新的終端,cd 存放imu_calibration.bag的路徑。
source ~/imu_catkin_ws/devel/setup.sh 
cd ~/imu_catkin_ws //數(shù)據(jù)包在這個(gè)文件夾下
rosbag play -r 400 imu_calibration.bag  其中 -r 400是指400速播放bag數(shù)據(jù)

標(biāo)定結(jié)果

標(biāo)定結(jié)束后在imu_catkin_ws/src/imu_utils/data中生成許多文件,其中d435i_imu_param.yaml就是我們想要的結(jié)果
Ubuntu 20.04 Intel RealSense D435i 相機(jī)標(biāo)定教程,# C++視覺處理,ubuntu,數(shù)碼相機(jī),linux這是我的

%YAML:1.0
---
type: IMU
name: d435i
Gyr:
   unit: " rad/s"
   avg-axis:
      gyr_n: 2.3713647521442301e-03
      gyr_w: 1.6634786328395575e-05
   x-axis:
      gyr_n: 2.5527723048677621e-03
      gyr_w: 1.8248792841502254e-05
   y-axis:
      gyr_n: 3.5989014238402488e-03
      gyr_w: 2.4626070373926136e-05
   z-axis:
      gyr_n: 9.6242052772467902e-04
      gyr_w: 7.0294957697583380e-06
Acc:
   unit: " m/s^2"
   avg-axis:
      acc_n: 1.2272815309641657e-02
      acc_w: 2.2269630970713836e-04
   x-axis:
      acc_n: 1.0855035063883016e-02
      acc_w: 1.9977097068680263e-04
   y-axis:
      acc_n: 1.2175166782188903e-02
      acc_w: 1.8151134885911570e-04
   z-axis:
      acc_n: 1.3788244082853051e-02
      acc_w: 2.8680660957549681e-04

realsense自帶的參數(shù):

roslaunch realsense2_camera rs_camera.launch
rostopic echo /camera/accel/imu_info 
rostopic echo /camera/gyro/imu_info

雙目標(biāo)定

創(chuàng)建april_6x6_A4.yaml文件

target_type: 'aprilgrid' #gridtype
tagCols: 6               #number of apriltags
tagRows: 6               #number of apriltags
tagSize: 0.021           #這個(gè)為a要親自拿尺子量一下
tagSpacing: 0.308          #這個(gè)就是b/a

Ubuntu 20.04 Intel RealSense D435i 相機(jī)標(biāo)定教程,# C++視覺處理,ubuntu,數(shù)碼相機(jī),linux

關(guān)閉結(jié)構(gòu)光

roslaunch realsense2_camera rs_imu_calibration.launch
rosrun rqt_reconfigure rqt_reconfigure

Ubuntu 20.04 Intel RealSense D435i 相機(jī)標(biāo)定教程,# C++視覺處理,ubuntu,數(shù)碼相機(jī),linux

rviz

Ubuntu 20.04 Intel RealSense D435i 相機(jī)標(biāo)定教程,# C++視覺處理,ubuntu,數(shù)碼相機(jī),linux

修改相機(jī)的幀數(shù)(官方推薦是4Hz)

rosrun topic_tools throttle messages /camera/color/image_raw 4.0 /color
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

錄制ROS數(shù)據(jù)包

rosbag record -O multicameras_calibration /infra_left /infra_right /color

bag文件屬性信息:

rosbag info multicameras_calibration.bag

使用Kalibr標(biāo)定

注意:標(biāo)定前先關(guān)掉相機(jī),否者會(huì)報(bào)錯(cuò)

source devel/setup.bash
//kalibr_calibrate_cameras --target /位置/文件名.yaml --bag /位置/camd435i.bag --bag-from-to 26 100 --models pinhole-radtan --topics /color --show-extraction

kalibr_calibrate_cameras --target april_6x6_A4.yaml --bag  multicameras_calibration.bag --models pinhole-equi pinhole-equi pinhole-equi --topics /infra_left /infra_right /color --bag-from-to 10 100 --show-extraction

報(bào)錯(cuò):ImportError: No module named wx
sudo apt-get install python3-wxgtk4.0
sudo apt-get install python3-igraph
sudo apt-get install python3-scipy

Ubuntu 20.04 Intel RealSense D435i 相機(jī)標(biāo)定教程,# C++視覺處理,ubuntu,數(shù)碼相機(jī),linux

multicameras_calibration-camchain.yaml

cam0:
  cam_overlaps: [1, 2]
  camera_model: pinhole
  distortion_coeffs: [0.42241273556155506, 0.20864813180833605, 0.3979238261062836, 0.5898003650060837]
  distortion_model: equidistant
  intrinsics: [394.73897935327875, 397.07609983064, 328.08812327934135, 229.9742739261273]
  resolution: [640, 480]
  rostopic: /infra_left
cam1:
  T_cn_cnm1:
  - [0.9994978959284028, -0.0004960676303391997, 0.031681381781581835, -0.049405645049756246]
  - [0.0006353578883581325, 0.9999901766268545, -0.00438668099301463, 1.6793675995192084e-05]
  - [-0.03167889447310175, 0.004404607438456279, 0.9994883926681007, 0.0014256336467758425]
  - [0.0, 0.0, 0.0, 1.0]
  cam_overlaps: [0, 2]
  camera_model: pinhole
  distortion_coeffs: [0.5127606598499351, -0.5373699037573214, 3.847162303528836, -5.204634833610096]
  distortion_model: equidistant
  intrinsics: [395.31081333647796, 396.67650876842976, 315.71216250025896, 232.01383312375893]
  resolution: [640, 480]
  rostopic: /infra_right
cam2:
  T_cn_cnm1:
  - [0.9991511714157386, 0.020802684247929682, -0.03555537915201736, 0.06452938946495283]
  - [-0.020609341536016703, 0.9997708061292826, 0.005795709884189747, -0.0014703526867445732]
  - [0.035667796399758, -0.005058017367587453, 0.9993509017158588, -0.0007200130467801373]
  - [0.0, 0.0, 0.0, 1.0]
  cam_overlaps: [0, 1]
  camera_model: pinhole
  distortion_coeffs: [0.3039064497137355, 2.82427913352034, -12.205548022168468, 18.250389840037823]
  distortion_model: equidistant
  intrinsics: [617.5837233756131, 622.6983038282931, 334.8320211033824, 228.30163838242865]
  resolution: [640, 480]
  rostopic: /color

multicameras_calibration-results-cam.txt

Calibration results 
====================
Camera-system parameters:
cam0 (/infra_left):
    type: <class 'aslam_cv.libaslam_cv_python.EquidistantDistortedPinholeCameraGeometry'>
    distortion: [0.42241274 0.20864813 0.39792383 0.58980037] +- [0.00610485 0.032712   0.08188243 0.11031642]
    projection: [394.73897935 397.07609983 328.08812328 229.97427393] +- [0.19306522 0.20612486 0.24778634 0.28703445]
    reprojection error: [0.000124, 0.000100] +- [0.657585, 0.919360]

cam1 (/infra_right):
    type: <class 'aslam_cv.libaslam_cv_python.EquidistantDistortedPinholeCameraGeometry'>
    distortion: [ 0.51276066 -0.5373699   3.8471623  -5.20463483] +- [0.00641909 0.03425317 0.07009558 0.09962364]
    projection: [395.31081334 396.67650877 315.7121625  232.01383312] +- [0.21098982 0.21177575 0.24814252 0.27660172]
    reprojection error: [0.000054, 0.000101] +- [0.574125, 0.899336]

cam2 (/color):
    type: <class 'aslam_cv.libaslam_cv_python.EquidistantDistortedPinholeCameraGeometry'>
    distortion: [  0.30390645   2.82427913 -12.20554802  18.25038984] +- [0.01032272 0.08120627 0.17338616 0.1112109 ]
    projection: [617.58372338 622.69830383 334.8320211  228.30163838] +- [0.2006613  0.19860848 0.35937867 0.42222736]
    reprojection error: [0.000159, 0.000139] +- [0.970352, 1.187701]

baseline T_1_0:
    q: [-0.0021981  -0.0158421  -0.00028289  0.99987205] +- [0.00041294 0.00031982 0.00009754]
    t: [-0.04940565  0.00001679  0.00142563] +- [0.00005321 0.00004922 0.0001863 ]

baseline T_2_1:
    q: [0.00271402 0.01780964 0.01035524 0.99978409] +- [0.00043723 0.00034848 0.00010065]
    t: [ 0.06452939 -0.00147035 -0.00072001] +- [0.00005198 0.00004369 0.00017821]



Target configuration
====================

  Type: aprilgrid
  Tags: 
    Rows: 6
    Cols: 6
    Size: 0.021 [m]
    Spacing 0.006468000000000001 [m]

imu+雙目標(biāo)定

創(chuàng)建:camchain.yaml:

gedit camchain.yaml
cam0:
  camera_model: pinhole
  intrinsics: [394.73897935327875, 397.07609983064, 328.08812327934135, 229.9742739261273]
  distortion_model: equidistant
  distortion_coeffs: [0.42241273556155506, 0.20864813180833605, 0.3979238261062836, 0.5898003650060837]
  rostopic: /infra_left
  resolution: [640, 480]
cam1:
  T_cn_cnm1:
  - [0.9994978959284028, -0.0004960676303391997, 0.031681381781581835, -0.049405645049756246]
  - [0.0006353578883581325, 0.9999901766268545, -0.00438668099301463, 1.6793675995192084e-05]
  - [-0.03167889447310175, 0.004404607438456279, 0.9994883926681007, 0.0014256336467758425]
  - [0.0, 0.0, 0.0, 1.0]
  camera_model: pinhole
  intrinsics: [395.31081333647796, 396.67650876842976, 315.71216250025896, 232.01383312375893]
  distortion_model: equidistant
  distortion_coeffs: [0.5127606598499351, -0.5373699037573214, 3.847162303528836, -5.204634833610096]
  
  rostopic: /infra_right
  resolution: [640, 480]

創(chuàng)建: imu.yaml
gedit imu.yaml

#Accelerometers
accelerometer_noise_density: 1.2272815309641657e-02   #Noise density (continuous-time)
accelerometer_random_walk:   2.2269630970713836e-04   #Bias random walk

#Gyroscopes
gyroscope_noise_density:     2.3713647521442301e-03   #Noise density (continuous-time)
gyroscope_random_walk:       1.6634786328395575e-05   #Bias random walk

rostopic:                    /imu      #the IMU ROS topic
update_rate:                 200.0      #Hz (for discretization of the values above)

修改:rs_imu_stereo.launch

復(fù)制realsense-ros包中rs_camera.launch,重命名為rs_imu_stereo.launch,更改內(nèi)容為

<arg name="enable_sync"               default="false"/>
//改為:
<arg name="enable_sync"               default="true"/>

這樣來使imu和雙目數(shù)據(jù)時(shí)間對(duì)齊

<arg name="unite_imu_method"          default=""/>
//改為
<arg name="unite_imu_method"          default="linear_interpolation"/>

開啟相機(jī)

roslaunch realsense2_camera rs_imu_calibration.launch

關(guān)閉IR結(jié)構(gòu)光,參考上面

rosrun rqt_reconfigure rqt_reconfigure

錄制 相機(jī) 和 imu 的聯(lián)合數(shù)據(jù)

調(diào)整 相機(jī) 和 imu 的 topic 的發(fā)布頻率以及以新的topic名發(fā)布它們,其中雙目圖像的發(fā)布頻率改為20Hz,imu發(fā)布頻率改為200Hz

rosrun topic_tools throttle messages /camera/color/image_raw 4.0 /color
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  imu_stereo.bag

注意:完成錄制后把相機(jī)關(guān)掉,和其他的發(fā)布的話題也關(guān)閉

運(yùn)行

rosrun  kalibr kalibr_calibrate_imu_camera --bag  imu_stereo.bag --cam  camchain.yaml --imu imu.yaml --target april_6x6_A4.yaml --bag-from-to 10 50 --show-extraction

Ubuntu 20.04 Intel RealSense D435i 相機(jī)標(biāo)定教程,# C++視覺處理,ubuntu,數(shù)碼相機(jī),linux

其中:

--target ../Aprilgrid/april_6x6_50x50cm_A4.yaml是標(biāo)定板的配置文件,如果選擇棋格盤,注意targetCols和targetRows表示的是內(nèi)側(cè)角點(diǎn)的數(shù)量,不是格子數(shù)量。
--bag ../multicameras_calibration_2020-10-29-20-19-06.bag是錄制的數(shù)據(jù)包;
--models pinhole-equi pinhole-equi pinhole-equi表示三個(gè)攝像頭的相機(jī)模型和畸變模型(解釋參考https://github.com/ethz-asl/kalibr/wiki/supported-models,根據(jù)需要選取);
--topics /infra_left /infra_right /color表示三個(gè)攝像頭對(duì)應(yīng)的拍攝的數(shù)據(jù)話題;
–bag-from-to 10 100表示處理bag中10-100秒的數(shù)據(jù)。(我在實(shí)驗(yàn)過程中沒有加–bag-from-to 10 100,所以處理的是bag里所有的數(shù)據(jù),標(biāo)定時(shí)間比較長)
–show-extraction表示顯示檢測(cè)特征點(diǎn)的過程。
這些參數(shù)可以相應(yīng)的調(diào)整。
imu_stereo-camchain-imucam.yaml
cam0:
  T_cam_imu:
  - [0.9998706466800502, -0.0005514101338320241, 0.016074385042181456, -0.009727195729487593]
  - [0.0004398826122011197, 0.9999758147457678, 0.0069409240614884855, 0.002409052480480027]
  - [-0.016077823574958232, -0.006932955387435725, 0.99984670710999, -0.02941555702845951]
  - [0.0, 0.0, 0.0, 1.0]
  camera_model: pinhole
  distortion_coeffs: [0.42241273556155506, 0.20864813180833605, 0.3979238261062836, 0.5898003650060837]
  distortion_model: equidistant
  intrinsics: [394.73897935327875, 397.07609983064, 328.08812327934135, 229.9742739261273]
  resolution: [640, 480]
  rostopic: /infra_left
  timeshift_cam_imu: -0.01115013714316784
cam1:
  T_cam_imu:
  - [0.9988590216788663, -0.0012668345078801814, 0.047739396111261004, -0.06006107726015477]
  - [0.0011456822768613126, 0.9999960539310532, 0.0025650603195308754, 0.0025486789058311375]
  - [-0.04774245723524004, -0.0025074394612811563, 0.9988565315021419, -0.02765611642952738]
  - [0.0, 0.0, 0.0, 1.0]
  T_cn_cnm1:
  - [0.9994978959284052, -0.0004960676303391998, 0.03168138178158184, -0.049405645049756246]
  - [0.0006353578883581324, 0.999990176626857, -0.004386680993014631, 1.6793675995192084e-05]
  - [-0.03167889447310176, 0.00440460743845628, 0.9994883926681032, 0.0014256336467758425]
  - [0.0, 0.0, 0.0, 1.0]
  camera_model: pinhole
  distortion_coeffs: [0.5127606598499351, -0.5373699037573214, 3.847162303528836, -5.204634833610096]
  distortion_model: equidistant
  intrinsics: [395.31081333647796, 396.67650876842976, 315.71216250025896, 232.01383312375893]
  resolution: [640, 480]
  rostopic: /infra_right
  timeshift_cam_imu: -0.01179951195993147
imu_stereo-imu.yaml
imu0:
  T_i_b:
  - [1.0, 0.0, 0.0, 0.0]
  - [0.0, 1.0, 0.0, 0.0]
  - [0.0, 0.0, 1.0, 0.0]
  - [0.0, 0.0, 0.0, 1.0]
  accelerometer_noise_density: 0.012272815309641657
  accelerometer_random_walk: 0.00022269630970713836
  gyroscope_noise_density: 0.00237136475214423
  gyroscope_random_walk: 1.6634786328395575e-05
  model: calibrated
  rostopic: /imu
  time_offset: 0.0
  update_rate: 200.0
imu_stereo-results-imucam.txt
Calibration results
===================
Normalized Residuals
----------------------------
Reprojection error (cam0):     mean 0.3935652501477467, median 0.34647466427290496, std: 0.24000390105212327
Reprojection error (cam1):     mean 0.40672475151297405, median 0.35408707621982244, std: 0.25805651611847996
Gyroscope error (imu0):        mean 0.25718333066848914, median 0.1978018986985239, std: 0.1868255561754322
Accelerometer error (imu0):    mean 0.16651624576366744, median 0.1500647834791136, std: 0.08979584592008485

Residuals
----------------------------
Reprojection error (cam0) [px]:     mean 0.3935652501477467, median 0.34647466427290496, std: 0.24000390105212327
Reprojection error (cam1) [px]:     mean 0.40672475151297405, median 0.35408707621982244, std: 0.25805651611847996
Gyroscope error (imu0) [rad/s]:     mean 0.008624941825093504, median 0.006633516506428987, std: 0.006265412106085885
Accelerometer error (imu0) [m/s^2]: mean 0.028901195472671417, median 0.026045816857109837, std: 0.015585309911764239

Transformation (cam0):
-----------------------
T_ci:  (imu0 to cam0): 
[[ 0.99987065 -0.00055141  0.01607439 -0.0097272 ]
 [ 0.00043988  0.99997581  0.00694092  0.00240905]
 [-0.01607782 -0.00693296  0.99984671 -0.02941556]
 [ 0.          0.          0.          1.        ]]

T_ic:  (cam0 to imu0): 
[[ 0.99987065  0.00043988 -0.01607782  0.00925194]
 [-0.00055141  0.99997581 -0.00693296 -0.00261829]
 [ 0.01607439  0.00694092  0.99984671  0.02955069]
 [ 0.          0.          0.          1.        ]]

timeshift cam0 to imu0: [s] (t_imu = t_cam + shift)
-0.01115013714316784


Transformation (cam1):
-----------------------
T_ci:  (imu0 to cam1): 
[[ 0.99885902 -0.00126683  0.0477394  -0.06006108]
 [ 0.00114568  0.99999605  0.00256506  0.00254868]
 [-0.04774246 -0.00250744  0.99885653 -0.02765612]
 [ 0.          0.          0.          1.        ]]

T_ic:  (cam1 to imu0): 
[[ 0.99885902  0.00114568 -0.04774246  0.05866926]
 [-0.00126683  0.99999605 -0.00250744 -0.0026941 ]
 [ 0.0477394   0.00256506  0.99885653  0.03048523]
 [ 0.          0.          0.          1.        ]]

timeshift cam1 to imu0: [s] (t_imu = t_cam + shift)
-0.01179951195993147

Baselines:
----------
Baseline (cam0 to cam1): 
[[ 0.9994979  -0.00049607  0.03168138 -0.04940565]
 [ 0.00063536  0.99999018 -0.00438668  0.00001679]
 [-0.03167889  0.00440461  0.99948839  0.00142563]
 [ 0.          0.          0.          1.        ]]
baseline norm:  0.04942621243940179 [m]


Gravity vector in target coords: [m/s^2]
[-0.33626366 -9.79119923 -0.43332124]


Calibration configuration
=========================

cam0
-----
  Camera model: pinhole
  Focal length: [394.73897935327875, 397.07609983064]
  Principal point: [328.08812327934135, 229.9742739261273]
  Distortion model: equidistant
  Distortion coefficients: [0.42241273556155506, 0.20864813180833605, 0.3979238261062836, 0.5898003650060837]
  Type: aprilgrid
  Tags: 
    Rows: 6
    Cols: 6
    Size: 0.021 [m]
    Spacing 0.006468000000000001 [m]

cam1
-----
  Camera model: pinhole
  Focal length: [395.31081333647796, 396.67650876842976]
  Principal point: [315.71216250025896, 232.01383312375893]
  Distortion model: equidistant
  Distortion coefficients: [0.5127606598499351, -0.5373699037573214, 3.847162303528836, -5.204634833610096]
  Type: aprilgrid
  Tags: 
    Rows: 6
    Cols: 6
    Size: 0.021 [m]
    Spacing 0.006468000000000001 [m]



IMU configuration
=================

IMU0:
 ----------------------------
  Model: calibrated
  Update rate: 200.0
  Accelerometer:
    Noise density: 0.012272815309641657 
    Noise density (discrete): 0.17356381859395387 
    Random walk: 0.00022269630970713836
  Gyroscope:
    Noise density: 0.00237136475214423
    Noise density (discrete): 0.03353616193815883 
    Random walk: 1.6634786328395575e-05
  T_ib (imu0 to imu0)
    [[1. 0. 0. 0.]
     [0. 1. 0. 0.]
     [0. 0. 1. 0.]
     [0. 0. 0. 1.]]
  time offset with respect to IMU0: 0.0 [s]

參考
https://blog.csdn.net/qq_38364548/article/details/124917067
https://blog.csdn.net/qq_44998513/article/details/132713079文章來源地址http://www.zghlxwxcb.cn/news/detail-792458.html

到了這里,關(guān)于Ubuntu 20.04 Intel RealSense D435i 相機(jī)標(biāo)定教程的文章就介紹完了。如果您還想了解更多內(nèi)容,請(qǐng)?jiān)谟疑辖撬阉鱐OY模板網(wǎng)以前的文章或繼續(xù)瀏覽下面的相關(guān)文章,希望大家以后多多支持TOY模板網(wǎng)!

本文來自互聯(lián)網(wǎng)用戶投稿,該文觀點(diǎn)僅代表作者本人,不代表本站立場(chǎng)。本站僅提供信息存儲(chǔ)空間服務(wù),不擁有所有權(quán),不承擔(dān)相關(guān)法律責(zé)任。如若轉(zhuǎn)載,請(qǐng)注明出處: 如若內(nèi)容造成侵權(quán)/違法違規(guī)/事實(shí)不符,請(qǐng)點(diǎn)擊違法舉報(bào)進(jìn)行投訴反饋,一經(jīng)查實(shí),立即刪除!

領(lǐng)支付寶紅包贊助服務(wù)器費(fèi)用

相關(guān)文章

  • Realsense d435i驅(qū)動(dòng)安裝、配置及校準(zhǔn)

    Realsense d435i驅(qū)動(dòng)安裝、配置及校準(zhǔn)

    寫在前面 本文是在ubuntu20.04下安裝,其它版本大同小異??赡艹霈F(xiàn)的問題,主要由各自安裝相關(guān)庫版本不一致導(dǎo)致,故問題不一,但一般很好解決,正常情況下不會(huì)出現(xiàn)。 Intel Realsense 深度攝像頭D435i將D435強(qiáng)大的深度感知能力和慣性測(cè)量單元(IMU)結(jié)合起來,可滿足RGBD、單目、

    2024年02月02日
    瀏覽(56)
  • realsense D435i 實(shí)現(xiàn)外部時(shí)鐘觸發(fā)硬件同步多相機(jī)數(shù)據(jù)采集

    realsense D435i 實(shí)現(xiàn)外部時(shí)鐘觸發(fā)硬件同步多相機(jī)數(shù)據(jù)采集

    最近有一個(gè)調(diào)試D435i相機(jī)的工作,需要使得三個(gè)相機(jī)能夠完成硬件觸發(fā)的同步,具體來說,就是有一個(gè)固定頻率的外部脈沖信號(hào),使得三個(gè)相機(jī)能夠根據(jù)外部脈沖信號(hào)的硬件觸發(fā)完成雙目圖片、深度圖片、彩色圖片、IMU數(shù)據(jù)的實(shí)時(shí)響應(yīng)采集,因?yàn)橥獠棵}沖信號(hào)是通過一個(gè)精確

    2024年01月16日
    瀏覽(301)
  • Ubuntu 18.04安裝D435i 相機(jī)驅(qū)動(dòng)及Ros1 Wrapper

    Ubuntu 18.04安裝D435i 相機(jī)驅(qū)動(dòng)及Ros1 Wrapper

    1.安裝前注意 librealsense SDK相當(dāng)于相機(jī)的驅(qū)動(dòng),SR300和ZR300的支持驅(qū)動(dòng)是librealsense SDK 1.0,而D435i是librealsense SDK 2.0 **安裝前一定要注意librealsense,realsense-ros(即Ros Wrapper),D435i相機(jī)固件版本三者之間的版本對(duì)應(yīng)關(guān)系。**ros1環(huán)境只支持librealsense2.50.0之前的版本,ros2環(huán)境要下載librealse

    2024年02月22日
    瀏覽(26)
  • Realsense D435i Yolov5目標(biāo)檢測(cè)實(shí)時(shí)獲得目標(biāo)三維位置信息

    Realsense D435i Yolov5目標(biāo)檢測(cè)實(shí)時(shí)獲得目標(biāo)三維位置信息

    - Colorimage: - Colorimage and depthimage: 1.一個(gè)可以運(yùn)行YOLOv5的python環(huán)境 2.一個(gè)realsense相機(jī)和pyrealsense2庫 在下面兩個(gè)環(huán)境中測(cè)試成功 win10 python 3.8 Pytorch 1.10.2+gpu CUDA 11.3 NVIDIA GeForce MX150 ubuntu16.04 python 3.6 Pytorch 1.7.1+cpu 修改模型配置文件,以yolov5s為例。 如果使用自己訓(xùn)練的模型,需要進(jìn)

    2024年02月04日
    瀏覽(50)
  • 【深度相機(jī)D435i】Windows+Ubuntu下調(diào)用D435i利用Python讀取、保存RGB、Depth圖片

    【深度相機(jī)D435i】Windows+Ubuntu下調(diào)用D435i利用Python讀取、保存RGB、Depth圖片

    最近組里面的項(xiàng)目需要用到D435i深度相機(jī)采集深度圖片,所以記錄一下在Windows+Ubuntu的環(huán)境下使用D435i深度相機(jī)的流程,以及如何利用python讀取、保存常見的RGB、Depth圖片。 D435i 在小巧外形中采用英特爾模塊和視覺處理器,是一個(gè)功能強(qiáng)大的一體產(chǎn)品,可與可定制軟件配合使用

    2024年02月02日
    瀏覽(36)
  • 項(xiàng)目設(shè)計(jì):YOLOv5目標(biāo)檢測(cè)+機(jī)構(gòu)光相機(jī)(intel d455和d435i)測(cè)距

    項(xiàng)目設(shè)計(jì):YOLOv5目標(biāo)檢測(cè)+機(jī)構(gòu)光相機(jī)(intel d455和d435i)測(cè)距

    1.1??Intel D455 Intel D455 是一款基于結(jié)構(gòu)光(Structured Light)技術(shù)的深度相機(jī)。 與ToF相機(jī)不同,結(jié)構(gòu)光相機(jī)使用另一種方法來獲取物體的深度信息。它通過投射可視光譜中的紅外結(jié)構(gòu)光圖案,然后從被拍攝物體表面反射回來的圖案重建出其三維形狀和深度信息。 Intel D455 深度相機(jī)

    2024年02月08日
    瀏覽(33)
  • (已修正精度 1mm左右)Realsense d435i深度相機(jī)+Aruco+棋盤格+OpenCV手眼標(biāo)定全過程記錄

    (已修正精度 1mm左右)Realsense d435i深度相機(jī)+Aruco+棋盤格+OpenCV手眼標(biāo)定全過程記錄

    最近幫別人做了個(gè)手眼標(biāo)定,然后我標(biāo)定完了大概精度能到1mm左右。所以原文中誤差10mm可能是當(dāng)時(shí)那個(gè)臂本身的坐標(biāo)系有問題。然后用的代碼改成了基于python的,放在下面。 新來的小伙伴可以只參考前面的代碼就可以完成標(biāo)定了。 有問題的話可以留言,一起交流~ 手眼標(biāo)定

    2024年02月04日
    瀏覽(49)
  • ORB-SLAM2的布置(五)使用 intel D435i 構(gòu)建SLAM點(diǎn)云地圖

    ORB-SLAM2的布置(五)使用 intel D435i 構(gòu)建SLAM點(diǎn)云地圖

    Intel RealSense SDK 2.0 是跨平臺(tái)的開發(fā)套裝,包含了基本的相機(jī)使用工具如 realsense-viewer,也為二次開發(fā)提供了豐富的接口,包括 ROS,python , Matlab, node.js, LabVIEW, OpenCV, PCL, .NET 等。 這次使用的攝像頭是D435i 它可以提供深度和 RGB 圖像,而且?guī)в?IMU 本次流程就是想使用D435i攝像頭進(jìn)

    2023年04月09日
    瀏覽(72)
  • d435i 相機(jī)和imu標(biāo)定

    d435i 相機(jī)和imu標(biāo)定

    使用 imu_utils 功能包標(biāo)定 IMU,由于imu_utils功能包的編譯依賴于code_utils,需要先編譯code_utils,主要參考 相機(jī)與IMU聯(lián)合標(biāo)定_熊貓飛天的博客-CSDN博客 Ubuntu20.04編譯并運(yùn)行imu_utils,并且標(biāo)定IMU_學(xué)無止境的小龜?shù)牟┛?CSDN博客 1.1 編譯 code_utils 創(chuàng)建工作空間 1.1.1 修改 CMakeLists.txt 文件

    2024年02月09日
    瀏覽(28)
  • ROS D435I識(shí)別目標(biāo)并獲取深度數(shù)據(jù)

    使用D435I相機(jī),并基于ros獲取到彩色圖像和匹配后的深度數(shù)據(jù),通過OPENCV對(duì)彩色圖像進(jìn)行目標(biāo)識(shí)別,得到目標(biāo)所在的像素范圍,隨后得到深度數(shù)據(jù) 重點(diǎn)在于:轉(zhuǎn)換ros圖像數(shù)據(jù)到opencv格式,得到目標(biāo)像素點(diǎn)的實(shí)際深度值 d435i啟動(dòng)與修改 使用上述指令啟動(dòng)d435i,可以在里面進(jìn)行分

    2024年02月10日
    瀏覽(22)

覺得文章有用就打賞一下文章作者

支付寶掃一掃打賞

博客贊助

微信掃一掃打賞

請(qǐng)作者喝杯咖啡吧~博客贊助

支付寶掃一掃領(lǐng)取紅包,優(yōu)惠每天領(lǐng)

二維碼1

領(lǐng)取紅包

二維碼2

領(lǐng)紅包