Isaac SimでNavigation2を実行する

今回はIsaac SimでNavigation2を使いJetBotを動かすことを試しました。

本記事は、以下のチュートリアルをもとに、Nova_CarterをJetBotに変更してNavigation2で動かした内容になります。
ROS2 Navigation — Omniverse IsaacSim latest documentation

※Navigation2に関しての事前知識なしでの取り組みのため、より簡単な方法があるかもしれません。

実行環境

Azureの仮想マシン(GPUを搭載したUbuntu 22.04のLinuxの仮想マシン)

  • サイズ: Standard NC4as T4 v3
  • vCPU 数: 4
  • RAM: 28 GiB

ROS2 Navigationのチュートリアルの実行

ROS2 Navigationのチュートリアルを実行するには、ROS2の環境を構築する必要があります。

ROS2のインストールに関しては以下のリンクを参考にしてください。

docs.omniverse.nvidia.com

ROS2をインストールし、Setting Up Workspacesの手順を実行すると、ROS2 Navigationのチュートリアルを実行する準備が完了します。

ROS2 Navigationのチュートリアルは以下のリンクを参考に行います。

docs.omniverse.nvidia.com

チュートリアルの内容を問題なく実行できたら、Nova_CarterをJetBotに変更しNavigation2で動かします。

Nova_CarterからJetBotへの変更

チュートリアルではNova_Carter_ROSのアセットを利用し、Navigation2で動かしています。

Nova_Carter_ROSからJetBotへ変更するために、追加する要素を見ていきます。


センサー

Nova Carterには、複数のセンサーが使われています。

  • 3D Lidarセンサー(PandarXT_32_10hz) 1つ
  • 2D Lidarセンサー(RPLIDAR_S2E) 2つ
  • imuセンサー 4つ

上記のうち3D Lidarセンサーが必須のセンサーになっています。

XT_32 > PandarXT_32_10hzの形でJetBotに追加します。

他のセンサーは追加しなくても、動作可能です。

そのほかのパーツ

後ほど追加するTransform_tree_odometoryのアクショングラフや、carter_navigation.launch.pyで利用されるcarter_navigation_params.yamlの内容を確認すると、base_frameとしてbase_linkが設定されています。

  • ロボットのベースリンク(base_link)

JetBotのアセットにはbase_linkが含まれていないため、chassisの下にbase_linkをXformで作成し追加します。

base_linkは、ロボットの座標フレームの基準点として機能するフレームの名称で、ロボットの物理的な中心や重心に配置され、ロボット全体の動きや位置を基準にするための参照点として使用されます。

Navigation2でbase_linkは以下の用途で利用されます。

  • コストマップ生成の基準
  • 自己位置推定の基準
  • 経路計画の基準
  • センサーデータの基準点

JetBotに3D Lidarセンサーとbase_linkを追加すると、以下のような構成になります。

※_hawkと_RPLidarはそれぞれimuセンサー、2D Lidarセンサー要素なので、追加していなくも問題ありません。

JetBotに3D Lidarセンサーとbase_linkを追加

Action graph

ROS2のトピックをpublish/subscribeするためのAction graphを追加します。

  • Ros_lidars: JetBotのフロントとリアに取り付けられた2D LIDARセンサーと3D LIDARセンサーからのデータをリアルタイムで処理し、ROS 2トピックにパブリッシュする
    • Isaac Create Render Product NodeのcameraPrimをJetBotに追加したPandarXT_32_10hzに設定
Ros_lidars
  • Transform_tree_odometory: シミュレーション環境でのロボットのオドメトリを計算し、ROS 2トピックに関連するトランスフォーム(TF)情報をパブリッシュする
    • ROS2Publish Transform Tree NodeのparentPrimを追加したbase_link、targetPrimをJetBotのchassisに設定
    • もう一つのROS2Publish Transform Tree NodeのparentPrimを追加したbase_link、targetPrimを追加したPandarXT_32_10hzに設定
    • Isaac Compute Odometory NodeのchassisPrimをJetBotのchassisに設定
transform_tree_odometory
  • differential_drive: 差動駆動ロボットの動作をシミュレーションするための機能を提供
    • Articulation controllerのtarget primにJetBotのprimを設定
    • differential controllerのmaxLinearSpeedを.22、wheelDistanceを.118、wheelRadiusを.0325に修正
differential_drive
  • Clock: Isaac SimとROS 2間でシミュレーション時間を同期し、ROS 2トピックにシミュレーション時間をパブリッシュする

トラブルシュート

RVIS2で表示した際にJetBotがマップに表示されない

JetBotにセンサーやAction graphを追加後、シミュレーションとNavigation2を実行すると、マップにJetBotが表示されないエラーが発生しました。

原因

frame [map] does not existの原因としては、以下の原因が考えれれます。

  • TFツリーの不整合
  • センサーデータのトピック名の不一致
解決方法

最終的な解決方法としては、JetBotに追加した3D LidarセンサーのPandarXT_32_10hzにName Overrideのプロパティを追加し、"front_3d_lidar"の値を設定することで解決しました。

name overrideの追加

carter_navigation.launch.pyで定義されているNodeのtarget_frameと3d Lidarセンサーの名称を同じに設定する必要があるようです。

Node(
    package='pointcloud_to_laserscan', executable='pointcloud_to_laserscan_node',
    remappings=[('cloud_in', ['/front_3d_lidar/lidar_points']),
                ('scan', ['/scan'])],
    parameters=[{
        'target_frame': 'front_3d_lidar', #これと同じ値を設定する
        'transform_tolerance': 0.01,
        'min_height': -0.4,
        'max_height': 1.5,
        'angle_min': -1.5708,  # -M_PI/2
        'angle_max': 1.5708,  # M_PI/2
        'angle_increment': 0.0087,  # M_PI/360.0
        'scan_time': 0.3333,
        'range_min': 0.05,
        'range_max': 100.0,
        'use_inf': True,
        'inf_epsilon': 1.0,
        # 'concurrency_level': 1,
    }],
    name='pointcloud_to_laserscan'
)

Lidarセンサーが障害物を誤検知する

JetBotがマップに表示され、Lidarセンサーでのスキャンが反映されると、何もない場所に障害物が検知されていました。

Lidarセンサーの誤検知
原因

Lidarセンサーが障害物を誤検知する場合、原因として以下のものが考えられます。

  • センサーのキャリブレーション不足
  • センサーの取り付け位置の問題
  • センサーデータのフィルタリング不足
  • コストマップ設定の問題
  • センサーデータの処理遅延
解決方法

障害物の誤検知は、carter_navigation.launch.pyで定義されているNodeの、min_heightの値を修正することで解決しました。

もともとNova_Carterのセンサーの設置高さに合わせて値が設定されているため、JetBotに設置したセンサーの高さに合わせて値を変更します。

JetBotの3D Lidarセンサーはz:0.07で設置しているため、値を-0.03に設定します。

修正後:

Node(
    package='pointcloud_to_laserscan', executable='pointcloud_to_laserscan_node',
    remappings=[('cloud_in', ['/front_3d_lidar/lidar_points']),
                ('scan', ['/scan'])],
    parameters=[{
        'target_frame': 'front_3d_lidar',
        'transform_tolerance': 0.01,
        'min_height': -0.03, #-0.4から値を修正,
        'max_height': 1.5,
        'angle_min': -1.5708,  # -M_PI/2
        'angle_max': 1.5708,  # M_PI/2
        'angle_increment': 0.0087,  # M_PI/360.0
        'scan_time': 0.3333,
        'range_min': 0.05,
        'range_max': 100.0,
        'use_inf': True,
        'inf_epsilon': 1.0,
        # 'concurrency_level': 1,
    }],
    name='pointcloud_to_laserscan'
)

これらのエラーを修正すると、チュートリアルと同様の動きをJetBotで再現することができました。

最後に

今回はJetBotのアセットを、Nova Carter用のNav2 launchファイル内容に合うように修正を行いました。

実機ではパーツの追加が難しいこともあるかと思うので、launchファイルやパラメーターファイルを修正しJetBotをNav2で動かすことや、仮想環境と実機両方で動かすことに挑戦してみたいです。

執筆担当者プロフィール
寺澤 駿

寺澤 駿(日本ビジネスシステムズ株式会社)

IoTやAzure Cognitive ServicesのAIを活用したデモ環境・ソリューション作成を担当。

担当記事一覧