ニュースNEWS

製品情報

2024.05.29

CuGoをROS 2で動かす!第2弾 Lidarを動かしてみよう

こんにちは。ロボットエンジニアの中村です。

クローラロボット開発プラットフォームをROS 2で動作させる連載の2回目です。今回は、Lidarを搭載してセンサデータを活用できるようにします。

トップ画像:メーカー様Webサイトより引用:https://www.slamtec.ai/product/slamtec-rplidar-s2/

 

前回はROS 2の/cmd_velトピックでロボットを動かしました。LidarでSLAMをする準備をこの記事で行います。LidarのROSパッケージをインストールし、ロボット上で動作させる方法を紹介します!

 

  • ROS 2を使ったCuGoの動かし方
  • ROS 2のLidarの使い方(この記事)
  • CartographerによるSLAMのやり方
  • EMCL2による自己位置推定のやり方
  • Navigation 2で自律走行のやり方

 

前回の記事はこちら!

ROS 2でCuGoを動かしてみよう(クローラロボット開発プラットフォームROS対応企画第1回)

 

Lidarとは

Lidar(Light Detection and Ranging)とは、赤外光を用いて物体との距離を測るセンサです。この記事で搭載する2D Lidarは下図のようにロボット周辺の環境を知ることができます。工場のAGVや配膳ロボットなどに使えば、ロボットの近くにある障害物を検知して、停止や回避を行うことができます。この連載では、このセンサによる自己位置推定とROS 2のNavigation 2を組み合わせて、ロボットの自律移動を実現する方法を説明します。

 

赤外線の反射時間を計測して距離を求めます。

メーカー様Webサイトより引用:https://www.slamtec.ai/product/slamtec-rplidar-s2/

 

360度分の距離を計測することで2次元平面の周辺環境を取得できます。

メーカー様Webサイトより引用:https://www.slamtec.ai/product/slamtec-rplidar-s2/

 

Lidarを取り付けてみた

それでは、実際にロボットにLidarを取り付けてみてROS 2で使用できるようにしましょう。前回はクローラロボット開発プラットフォーム CuGo V3iにPCを載せられるようにアルミフレームでやぐらを組みました。

 

2DLidarはSLAMTEC社のRPLIDAR S2を選定しました。今回は簡易に実験を行うため、Lidarの裏面に両面テープを貼り、ロボットの電装ボックスに取り付けました。箱を開けたときにケーブルが引っかからないように、箱のヒンジ側からケーブルを通し、アルミフレームに沿わせてPCに接続します。PCにUSBケーブルを接続することでROS 2でLidarのセンサデータを取得できるようになります。

 

PCとの接続構成

前回の記事で接続したLD-2と今回取り付けたLidarを合わせると以下の図のような構成になります。

LD-2からモータの回転数を取得し、Lidarからロボット周辺の物体までの距離を取得します。自律移動をするときは、この情報を使ってロボットの次の行動を計算し、LD-2にモータの回転数指示を送ることでロボットが走行します。

 

Lidarを動かしてみよう

接続したLidarをROS 2で動かしてみましょう。

使用しているLidarのRPLIDAR S2はSLAMTEC社が公式のROS 2パッケージを公開しています。この公式パッケージをインストールして実行することでLidarを動かします。

 

RPLiDAR 公式パッケージ:https://github.com/Slamtec/rplidar_ros

 

SLAMTEC製のROSパッケージであるrplidar_rosを使ってみましょう。

まず、ROSの作業スペースに移動してから、rplidar_rosのリポジトリをクローンし、ビルドします。この時、rplidar_rosのリポジトリはROS1のソースコードがデフォルトで表示されているので(masterブランチ)、ROS 2で動作するブランチをクローンします。ros2ブランチのソースコードをクローンするために-b オプションでros2 ブランチを指定します(Humble / Jazzy共通です)。

 

次のコマンドを入力します。


$ cd /move/to/your/ros_2/directory/colcon_ws/src
$ git clone https://github.com/Slamtec/rplidar_ros.git -b ros2
$ cd ..
$ colcon build

 

ここでエラーが出なければLidarが動きます。ワーニングがたくさん出ますが、rplidar_rosの文法の書き方が少し古いためです。問題ないので実行してみましょう。

 

次に、USB通信の設定をします。USBケーブルを接続しただけでは、読み書き権限がなく通信できません。Lidarに対して読み書き権限を与えます(前回の記事と同じ操作をします)。


$ ls /dev/tty*

 

この画面では、ttyUSB0がLidarです。ttyUSB0の数字の部分は環境によって変化します。Lidarを抜き差しして表示されるデバイスの変化を見て、Lidarのポート名を調べてください。

 

Lidarに対して読み書き権限を与えます。


$ sudo chmod 777 /dev/ttyUSB0

これでLidarから送られてきたデータを読み取ることができます。

 

次に、rplidar_rosを起動します。今回使用する製品はRPLIDAR S2ですので、S2専用の起動コマンドを入力します。


ros2 launch rplidar_ros view_rplidar_s2_launch.py

 

他のRPLIDARを起動したい場合は、GitHubの起動コマンドを参考にしてください。

引用:https://github.com/Slamtec/rplidar_ros

↑他の製品はGithubのREADMEを参考にしてください。

 

上記の起動コマンドを実行すると、自動的にビジュアライズツールのRviz2が起動し、Lidarのセンサデータを見ることができます。

 

うまくいくと、図のようにLidarのセンサデータが可視化されます。周囲の障害物と比較して、正しくデータが取れているか、手を動かしてみてデータが動いていく様子を見てみましょう。

 

障害物を消してみよう

Lidarを起動してデータを確認することができました。これですぐに自律走行ができます!と言いたいところですが、ロボットにLidarを搭載するときにそのままの状態のセンサデータでは使えないことが多いです。例えば、写真のようにロボットの構造物をLiDARが認識してしまい、障害物として扱ってしまうことがあります。

 

RPLIDAR S2のセンサデータは360度分の距離が利用できますが、ロボットの構造物によって使えないデータを棄却することができます。今回はデータの棄却を行うために、ROS 2で標準的に配布されているlaser_filtersを利用します。

 

laser_filtersパッケージ:https://github.com/ros-perception/laser_filters

 

laser_filtersをインストールします。

Jazzyバージョンの方はこちら


$ sudo apt install ros-jazzy-laser-filters

 

Humbleバージョンの方はこちら


$ sudo apt install ros-humble-laser-filters

 

laser_filtersの機能ではさまざまなフィルタをかけた値を出力することができます。ロボットの構造物を取り除くには以下の3種類のフィルタが有効です。

 

Filterの種類 効果
Footprint Filter Lidarを中心とした円形の範囲のセンサデータを削除する。指定した半径r以下の範囲を削除する
Anguler Filter 指定した角度のセンサデータを削除する。〇度~×度の範囲を消すと指定する
Box Filter 指定した四角形の位置のセンサデータを削除する。四角形の左上と右下の座標(x,y)をそれぞれ指定する。

 

大まかにこの3つのフィルタのどれかを使用するとたいていのロボットでLidarの前処理ができます。今回は、

 

  • ロボットの柱を検出するビームの角度はほとんど変わることがない
  • Lidarの統計処理の結果、物体から少し離れた位置に認識をする場合がある。Box Filterだとこれを取り除けない。
  • Footprint Filterは円形の範囲しか取り除けない。このロボットのように四角形の場合、円の半径の内側にある本当の障害物も取り除いてしまう。

 

以上の理由から、Anguler Filterを使用します。

 

laser_filtersの使用方法は、launchファイルで呼び出すだけです。launchファイルは複数のROSパッケージを起動したり、そのパッケージで使用するオプションやパラメータを自由に設定することができるものです。そこで、rplidar_rosを起動するlaunchファイルにlaser_filtersを起動する内容を書き加えます。

 

先ほど使用した、view_rplidar_s2_launch.pyに追記します。

# ↓ここを追加↓の範囲をコピー&ペーストしてください。

 

view_rplidar_s2_launch.py


#!/usr/bin/env python3

import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import LogInfo
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node


def generate_launch_description():
    channel_type =  LaunchConfiguration('channel_type', default='serial')
    serial_port = LaunchConfiguration('serial_port', default='/dev/ttyUSB0')
    serial_baudrate = LaunchConfiguration('serial_baudrate', default='1000000') #for s2 is 1000000
    frame_id = LaunchConfiguration('frame_id', default='laser')
    inverted = LaunchConfiguration('inverted', default='false')
    angle_compensate = LaunchConfiguration('angle_compensate', default='true')
    scan_mode = LaunchConfiguration('scan_mode', default='DenseBoost')

# 省略

				# rplidar_rosのノード起動設定
        Node(
            package='rplidar_ros',
            executable='rplidar_node',
            name='rplidar_node',
            parameters=[{'channel_type':channel_type,
                         'serial_port': serial_port,
                         'serial_baudrate': serial_baudrate,
                         'frame_id': frame_id,
                         'inverted': inverted,
                         'angle_compensate': angle_compensate,
                         'scan_mode': scan_mode}],
            output='screen'),
        
        # ↓ここを追加↓
        # lidar_filtersのノード起動設定
        Node(
            package   = 'laser_filters',
            executable= 'scan_to_scan_filter_chain',
            parameters=['/home/yuta/workspace/colcon_ws/src/rplidar_ros/launch/angular_filter_example.yaml'],
        )
        # ↑ここを追加↑
        
    ]

 

追加されたところにparametersと書かれた値があります。これはlaser_filtersのフィルタのパラメータが書かれたファイルを指定する場所を指定します。この例では絶対パスでrplidar_ros/launchディレクトリ内を指定しています。laser_filters公式のパラメータファイルをこのディレクトリにコピーしました。

 

angular_filter_example.yaml : https://github.com/ros-perception/laser_filters/blob/ros2/examples/angular_filter_example.yaml

 

この状態で再びlaunchファイルを実行します。

laser_filtersのサンプルのパラメータファイルは前方半分のlidarの値をすべて削除しています。このパラメータファイルを修正して、アルミフレームの部分をフィルタしたいと思います。

 

Angluer Filterで指示する値は以下の図のように、削除したい角度の範囲を弧度法で表現します。ロボット正面を0度とすると、反時計回りが正の方向、時計回りが負の方向で指示します。

Range Filter を適用するためにはconfigファイルを作ります。

rplidar_rosのリポジトリにはお手本のconfigファイルがあるので、これに実際にロボットが干渉する座標の情報に変更します。

以下のファイルをコピーして修正します。

 

angular_filter_example.yaml : https://github.com/ros-perception/laser_filters/blob/ros2/examples/angular_filter_example.yaml

 

launchファイルと同じディレクトリにbox_filter_example.yamlを配置すると、launchファイルでパスを指定しなくても利用することができます。

実際のロボットでは、以下の場所を取り除きます。

 

angular_filter_example.yaml


scan_to_scan_filter_chain:
  ros__parameters:
    filter1:
      name: angle1
      type: laser_filters/LaserScanAngularBoundsFilterInPlace
      params:
        lower_angle: 0.6
        upper_angle: 1.0
    filter2:
      name: angle2
      type: laser_filters/LaserScanAngularBoundsFilterInPlace
      params:
        lower_angle: -1.0
        upper_angle: -0.6
    filter3:
      name: angle3
      type: laser_filters/LaserScanAngularBoundsFilterInPlace
      params:
        lower_angle: 1.9
        upper_angle: 2.3
    filter4:
      name: angle4
      type: laser_filters/LaserScanAngularBoundsFilterInPlace
      params:
        lower_angle: -2.3
        upper_angle: -1.9

 

サンプルのコンフィグファイルからは以下の項目を変更しました。

 

  • filter1~filter4まで追加しました。
  • type をlaser_filters/LaserScanAngularBoundsFilterからlaser_filters/LaserScanAngularBoundsFilterInPlaceに変更しました。

 

先ほどコピーしたangular_filter_example.yamlを上記に変更しましょう。

変更した後、colcon buildをしてください。

これで準備が整いました。では、実行してみましょう。


$ ros2 launch rplidar_ros view_rplidar_s2_launch_laser_filter.py

 

 

↑rplidar_rosから出力された/scanトピック

 

↑laser_filtersから出力された/scan_filteredトピック

 

このようにロボットの機体のアルミフレームの柱を取り除くことができました。色を変えて2つのトピックを比較しました。赤が/scan_filteredトピック、白が/scanトピックです。ロボットのアルミフレーム部分がすべて取り除かれていることがわかります。

 

これで、自律走行をするためのセンサを準備することができました。次回は、このtopicを使って実際にSLAMをする工程を解説します。お楽しみに!!!

WEBからのお問い合わせ

ご相談はお問い合わせフォームをご利用ください。

お問い合わせフォームへ