10万円以下の3D-LiDAR: Livox 社製 MID-360 を使って、3D-MAP作成(LIO-Livox)を実装しました。

  • MID-360内蔵IMUを使用
  • 点群取得しながら3D-MAPを作成
  • 作成したデータをPCDファイルへ保存
3D-MAP作成(LIO-Livox)の画面イメージ

概要

システムアーキテクチャ

システムはノード「ScanRegistartion」から始まり、特徴点が抽出されます。
都市のシーンでは通常多くの動的オブジェクトが存在するため、特徴抽出の前に動的オブジェクトを点群から削除されます。
動的オブジェクトフィルターには、fast cloud segmentation手法を使用します。
ユークリッド クラスタリングは、点をいくつかのクラスターにグループ化するために適用されます。
点群は、地上点、背景点、および前景点に分割されます。
前景点は動的オブジェクトとみなされ、特徴抽出プロセスから除外されます。
動的オブジェクトフィルターにより、システムは動的シーンでも高い堅牢性を実現します。

システム構成図画像

ハードウエア構成

環境

  • ROS(Noetic)
  • Celes Solver

セットアップ

Celes Solverをインストール

インストール手順は以下を参照ください。

Ceres Solver Linux版インストール手順
  • ただし、バージョンは2.1.0を使用する
$ wget http://ceres-solver.org/ceres-solver-2.1.0.tar.gz
コピーしました

Livox_SDK2をインストール&セットアップgithub

Livox_ros_driver2をインストール&セットアップgithub

githubに公開されているLIO-Livoxのパッケージをダウンロードし、コンパイル

$ cd ~/livox_ws/src/
$ git clone https://github.com/ixs-yuichiro-okui/LIO-Livox.git
コピーしました

このまま、catkin_makeを実行しても、エラーが発生するので、以下を修正する

livox_ros_driver2 用にファイルを変更

  • 修正ファイル
    LIO-Livox/CMakeLists.txt、LIO-Livox/package.xml
    LIO-Livox/include/LidarFeatureExtractor/LidarFeatureExtractor.h
    LIO-Livox/src/lio/LidarFeatureExtractor.cpp
    LIO-Livox/src/lio/ScanRegistration.cpp
  • 修正内容
    livox_ros_driver => livox_ros_driver2

Noetic用にファイルを変更

  • 修正ファイル
    LIO-Livox/CMakeLists.txt
  • 修正内容
    set(CMAKE_CXX_FLAGS "-std=c++14")
  • 修正ファイル ⁄ github
    • include/Estimator/Estimator.h

    • src/lio/PoseEstimation.cpp

    • src/segment/segment.cpp概要

地図生成後のPCDファイルを保存できるように、ソースコードを修正

これにより、"Ctrl+c"にて処理を終了した後、PCDファイルが保存される

  • LIO-Liovx/src/lio/PoseEstimation.cpp
   :
38行目 ///// Add /////
39行目 pcl::PointCloud<pointype>::Ptr livox_full_map(new pcl::PointCloud<pointype>());
40行目 ///// Add /////
   :
570行目 ///// Add /////
571行目       *livox_full_map += *laserCloudAfterEstimate;
572行目 ///// Add /////
   :
628行目 ///// Add /////
629行目   std::string save_map_file;
630行目   ros::param::get("~save_map_file",save_map_file);
631行目   std::cout << "===== Save PCD file =====" << std::endl;
632行目   pcl::io::savePCDFileBinary(save_map_file, *livox_full_map);
633行目 ///// Add /////</pointype></pointype>
コピーしました

この後、コンパイルを実行

$ catkin_make
コピーしました

パラメータの設定

  • launchファイル:mid360.launch内の”IMU mode"とPCDファイル名を指定する
  • Voxel Filterの係数は必要に応じて変更してください
<launch>

<node pkg="lio_livox" type="ScanRegistration" name="ScanRegistration" output="screen">

    <param name="config_file" value="$(find lio_livox)/config/mid360_config.yaml"/>
    <!--0-custom msg ,1 ros sensor msg pointcloud2 msg  -->
    <param name="msg_type" type="int" value="0"/>
</node>

<node pkg="lio_livox" type="PoseEstimation" name="PoseEstimation" output="screen">
    <!-- 0-Not Use IMU, 1-Use IMU remove Rotation Distort, 2-Tightly Coupled IMU -->
    <param name="IMU_Mode" type="int" value="1" />
    <!-- Voxel Filter Size Use to Downsize Map Cloud -->
    <param name="filter_parameter_corner" type="double" value="0.2" />
    <param name="filter_parameter_surf" type="double" value="0.4" />
    <!-- Extrinsic Parameter between Lidar & IMU -->
    <rosparam param="Extrinsic_Tlb"> [0.9999161, 0.0026676,  0.0126707, -0.011,
                                        -0.0025826, 0.9999741, -0.0067201, -0.0234,
                                        -0.0126883, 0.0066868,  0.9998971,   0.044,
                                            0.0,       0.0,        0.0,      1.0]</rosparam>

    <param name="save_map_file" type="string" value="$(find lio_livox)/pcd/map.pcd" />
</node>

<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find lio_livox)/rviz_cfg/lio.rviz" />

</launch>
コピーしました

実行方法

$ roslaunch livox_ros_driver2 msg_MID360.launch
$ roslaunch lio_livox mid360.launch
コピーしました

点群ファイルの編集

作成したPCDファイルをCloudCompareを使って編集できます。

  • 加工前データ
    • SORフィルタ(離れた位置のデータを除去)
    • PCV/ShadeVis加工(エッジを強調)
    • 天井部分を削除
  • 加工後データ
参考

免責事項

本ページでご紹介したシステムは、あくまでもデモ用として確認しています。 従いまして、本ページ内容の活用による不具合などの責任は負いかねます。
また、商用利用する場合は、ソースコード作成元へ確認ください。