IMU標定及びAllan分散分析

5492 ワード

IMU-Xsens標定及びAllan分散分析
  • 1.コンパイル標定機能パッケージ
  • をダウンロードする
  • .IMUパケット
  • を録画する
  • 3.標定IMU
  • 4.Allan分散分析
  • 1.コンパイルパッケージのダウンロード
  • インストール依存
  • sudo apt-get install libdw-dev
    
  • ダウンロード標定コード
  • ダウンロード前の注意事項:
  • グローバルインストールceresライブラリ、code_utils依存ceres;
  • 同時にimuをutilsとcode_utilsは一緒にsrcの下に置いてコンパイルします.i mu_utils依存code_utils、だから先にcode_utilsはワークスペースのsrcの下に置いてコンパイルします.そしてimu_utilsはsrcの下に置いてからコンパイルします.
  • code_utilsの下にsumpixelが見つかりました.test.cpp,#include"backward.hpp"を#includeに変更し,再コンパイルする.エラーが発生しない場合:code_utils-master/src/sumpixel_test.cpp:2:24: fatal error: backward.hpp:No such file or directory ;
  • cd catkin_vio/src
    git clone https://github.com/gaowenliang/code_utils.git
    #   code_utils    sumpixel_test.cpp  #include "backward.hpp"  #include 
    cd ..
    catkin_make
    
    cd catkin_vio/src
    git clone https://github.com/gaowenliang/imu_utils.git
    cd ..
    catkin_make
    

    2.IMUパケットの録画
    IMUを2時間静止させ、IMUのパケットを録画する必要があります.
    rosbag record /imu/data
    

    3.標定IMU
    変更imu_utils機能パッケージのxsens.launch起動ファイル:
    標定時間の設定がbagの録画時間よりも小さいことに注意する.
    <launch>
    
        <node pkg="imu_utils" type="imu_an" name="imu_an" output="screen">
            <param name="imu_topic" type="string" value= "/imu/data"/>  # imu   
            <param name="imu_name" type="string" value= "xsens"/>
            <param name="data_save_path" type="string" value= "$(find imu_utils)/data/"/>
            <param name="max_time_min" type="int" value= "140"/>  #      
            <param name="max_cluster" type="int" value= "100"/>
        </node>
    
    </launch>
    

    標定の開始
    rosbag play -r 200 ~/Datasets/imu_xsens.bag
    roslaunch imu_utils xsens.launch
    

    標定結果
    %YAML:1.0
    ---
    type: IMU
    name: xsens
    Gyr:
       unit: " rad/s"
       avg-axis:
          gyr_n: 7.7614407939270297e-03
          gyr_w: 7.5651166306226329e-05
       x-axis:
          gyr_n: 7.7728977807653386e-03
          gyr_w: 6.0588972267830838e-05
       y-axis:
          gyr_n: 7.5955231310305170e-03
          gyr_w: 8.2351378468359284e-05
       z-axis:
          gyr_n: 7.9159014699852325e-03
          gyr_w: 8.4013148182488846e-05
    Acc:
       unit: " m/s^2"
       avg-axis:
          acc_n: 1.3016675257480200e-02
          acc_w: 4.7507975269777742e-04
       x-axis:
          acc_n: 1.3400641779288071e-02
          acc_w: 2.4554204072481519e-04
       y-axis:
          acc_n: 1.3126654194402345e-02
          acc_w: 5.7696613387170879e-04
       z-axis:
          acc_n: 1.2522729798750180e-02
          acc_w: 6.0273108349680833e-04
    

    4.Allan分散分析