【第2弾】Isaac Simで実現するAckermann車両モデルmibotのデジタルツインナビゲーション
![]() |
![]() |
---|
はじめに
プロジェクトの目的と背景
この記事では、IsaacSim上でAckermann車両モデルをデジタルツインの中でナビゲーションする方法を紹介します。
私は現在工学系の学部3年生で、この春から一人乗りの超コンパクトな電動マイクロカー『mibot』を開発する会社「KGモーターズ株式会社」でインターンをしています。
将来的にmibotは自動運転車としての実用化を目指しています。
その一環として、工場のデジタルツインを作り、mibotを工場内で走らせるシミュレーションに取り組みました。
今回の記事では、その目標に向けた第二弾として、KGモーターズ株式会社の拠点である Mibot Core Factory(MCF)のデジタルツインの中でmibotのナビゲーションを実現するまでの過程を紹介します。
Isaac Simは、高精細で美しい描画と現実的な物理・センサー挙動を備え、ロボットをPC上の仮想空間で検証できるシミュレーターで、以下のようなデジタルツインを構成することができます。
デジタルツインに関しては、第1弾をご参照ください!
本記事の対象読者
- Isaac Simでアッカーマン型の車両を動かしてみたいけれど、どこから手を付ければいいのかわからない初心者の方
- Isaac SimでLiDARの取り付け方、ナビゲーションするのに必要なトピックの通し方を知りたい方
- ROSを使ったロボットシミュレーションやナビゲーションに挑戦してみたい学生・エンジニアの方
私自身もまだ初心者で、Isaac Simでアッカーマン型の車両をナビゲーションさせる過程では多くのつまずきがありました。
だからこそ、この記事では「入門者が実際につまずいたポイントや解決までの流れ」を含めて、正直に記録していきます。これから同じようにIsaac Simで挑戦したい方にとって、少しでも参考になれば幸いです。
実行環境
Isaac SimをWorkStationでインストールして動かすための推奨環境は以下の通りです。
推奨環境 | |
---|---|
OS | Linux |
GPU | NVIDIA製、VRAM 8GB以上 |
Driver | 535.129.03以降 |
システムメモリ | 32GB以上 |
自分の環境で十分かどうか、まずCompatibility Checkerを入れて確かめることもできます。詳しくは以下の公式チュートリアルをご覧ください。
私は以下の環境で作業を行いました。
- CPU : AMD Ryzen 9 5900X
- メモリ : 32 GB
- GPU : NVIDIA GeForce RTX 3090(VRAM : 24 GB GDDR6X 搭載)
手順
1.ROS2・Nav2・workspaceのセットアップ
ROS2 Humbleは以下のリンク先の手順で
Nav2は以下のリンク先の手順でインストールできます。
また、IsaacSimが公開してくれているWorkspaceをクローンしておきます。
今回はhumble_ws中のスクリプトを利用します。
2.車両にLiDARを取り付ける
以下のようなmibotのurdfを用いてナビゲーションしていきます。
このurdfに関して、詳しく知りたい方は弊社のこちらの記事を是非ご参照ください。
まず、urdfファイルをインポートします。
IsaacSimの左上バーのFile>importからmibot.urdfを開きます。
このとき、右側の詳細設定で、LinksはMoveable Base
に、テーブルのName
がwheelから始まる4つのjoint(wheel_joint_front_left
, wheel_joint_front_right
, wheel_joint_rear_left
, wheel_joint_rear_right
)のTargetをPosition
からVelocity
に変更しておきます。
それでは、車両にLiDARを取り付けます。
車両(mibot)内の階層構造
-
mibot/base_link直下に base_scan(Xform) を作成
stageのbase_link を右クリックし、createからXform
を選ぶと作成できます。base_linkは車両の基準点のことで、この階下へbase_scanをおき、LiDARを設置していきます。
base_scanのPropertyから、TranslateをX:0.5, Y:0.0, Z:1.52
に設定します。これは、base_linkから見たLiDARを取り付けたい相対位置です。 -
左上バー Create>Sensors>RTX Lidar>Rotating(Camera) をbase_link直下に追加
これがLiDAR本体です。RTX_LiDARに改名しておきます。 -
左上バーCreate>Sensors>RTX Lidar>HESAI>XT-32 10hzをbase_link直下に追加
こちらはLiDARの外見です。 -
左上バーTools>Robotics>ROS2 OmniGraphs>RTX Lidarを選択しActionGraphを作成
以下のような画面が出てきますが、
Lidar Prim :/world/mibot/base_link/base_scan/RTX_LiDAR
、
Frame ID:base_scan
、
Laser_scan、Point Cloudにともにチェックをつけ、
Topic名をそれぞれ、/scan
,/point_cloud
と設定し、OKを押すと、既存のLiDAR用のアクショングラフを使うことができます。
LiDARを取り付けた車両の外観は以下のようになります。
3.ActionGraphの設定
LiDAR以外のActionGraphの設定もしていきます。
Ackermannの車両をナビゲーションするには、ナビゲーションするのに必要なトピックである、
-
/clock
(時刻) -
/tf
(座標変換) -
/odom
(初期位置からの相対位置・姿勢・速度) -
/scan
(LiDARの2D点群データ) -
/map
(地図、絶対座標)
を準備しなくてはなりません。
/scan
の設定は先ほど済ませたので、上の3つの設定をしていきましょう。同様にTools>Robotics>ROS2 OmniGraphsから追加することができます。
Clockはパラメータの入力は不要です。
TF Publisherでは、base_linkからbase_scan(LiDAR)の相対位置を設定しておきます。
Target Primを/World/mibot/base_link/base_scan
、
Parent Prim(default to /World) を/World/mibot/base_link
に設定します。Addを押せば、所望のPrimを選ぶことができます。
Odometry Publisherでは、Publish Robot’s TF? にチェックを入れ、Chassis Link Primが/World/mibot/base_link
であることを設定しておきます。
4.Mapの撮影
次に/map
を準備していきましょう。
チュートリアルを参考に今の環境の地図を撮影します。
右上のバーから、Tools>Robotics>Occupancy Mapを選択します。
左下のOccupancy Map extensionでUpper BoundのZ座標をZ:1.52
に設定します。これはLiDARの設置されている高さです。
BOUND SELECTION、CALCULATEを順に押して、地図の座標を計算し、VISUALIZE IMAGEを押します。
ここで、180度回転させ、ROS Occupancy Map Parameters File(YAML) を選んで、RE-GENERATE IMAGEを押します。画像はMCF_navigation.png
, YAMLファイルはMCF_navigation.yaml
という名前でhumble_ws>src>navigation>carter_navigation>mapsに保存します。
物体を配置しているのに地図に反映されない場合、Colliderの設定が抜けている可能性があります。該当オブジェクトをStage上で右クリックし、Add>Physics>Colliderを選択して設定してください。
5.launchファイル・paramファイルの書き換え
IsaacSimから提供されているスクリプトを、自分の環境に合わせて書き換えていきます。
humble_ws>src>navigation>carter_navigation中のlaunch>carter_navigation.launch.pyとparam>carter_navigation_param.yamlを拝借して環境に合わせて書き換え、それぞれMCF_navigation.launch.py, MCF_navigation_param.yamlとして保存します。
MCF_navigation.launch.pyでは、
- paramファイルとmapファイルの名称の書き換え
map_dir = LaunchConfiguration(
"map",
default=os.path.join(
- get_package_share_directory("carter_navigation"), "maps", "carter_warehouse_navigation.yaml"
+ get_package_share_directory("carter_navigation"), "maps", "MCF_navigation.yaml"
),
)
param_dir = LaunchConfiguration(
"params_file",
default=os.path.join(
- get_package_share_directory("carter_navigation"), "params", "carter_navigation_params.yaml"
+ get_package_share_directory("carter_navigation"), "params", "MCF_navigation_params.yaml"
),
)
- pointcloud_to_laserscan変換ノードの削除
-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': 11.0, #Original-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'
- )
MCF_navigation_param.yamlでは、
- LiDAR, mapのトピック名の変更
- scan_topic: scan
+ scan_topic: /scan
- map_topic: map
+ map_topic: /map
- 初期位置の修正
initial_pose:
- x: -6.0
- y: -1.0
- z: 0.0
- yaw: 3.14159
+ x: 13.0
+ y: 2.0
+ z: 0.0
+ yaw: 0.0
- フットプリント(車体のサイズ)の修正
local_costmap:
local_costmap:
ros__parameters:
# ...
- footprint: "[ [0.14, 0.25], [0.14, -0.25], [-0.607, -0.25], [-0.607, 0.25] ]"
+ footprint: "[ [1.245, 0.565], [1.245, -0.565], [-1.245, -0.565], [-1.245, 0.565] ]"
# ...
global_costmap:
global_costmap:
ros__parameters:
# ...
- footprint: "[ [0.14, 0.25], [0.14, -0.25], [-0.607, -0.25], [-0.607, 0.25] ]"
+ footprint: "[ [1.245, 0.565], [1.245, -0.565], [-1.245, -0.565], [-1.245, 0.565] ]"
- LiDARの構成・設定を修正
local_costmap:
local_costmap:
ros__parameters:
# ...
- plugins: ["hesai_voxel_layer", "front_rplidar_obstacle_layer", "back_rplidar_obstacle_layer", "inflation_layer"]
+ plugins: ["hesai_voxel_layer", "rplidar_obstacle_layer", "inflation_layer"]
# plugins: ["hesai_voxel_layer", "inflation_layer"]
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
enabled: True
cost_scaling_factor: 0.3
- inflation_radius: 1.0
+ inflation_radius: 1.5
hesai_voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
footprint_clearing_enabled: true
max_obstacle_height: 2.0
publish_voxel_map: False
origin_z: 0.0
z_voxels: 16
z_resolution: 0.2
unknown_threshold: 15
observation_sources: pointcloud
pointcloud: # no frame set, uses frame from message
- topic: /front_3d_lidar/lidar_points
+ topic: /point_cloud
max_obstacle_height: 2.0
min_obstacle_height: 0.1
obstacle_max_range: 10.0
obstacle_min_range: 0.0
raytrace_max_range: 10.0
raytrace_min_range: 0.0
clearing: True
marking: True
data_type: "PointCloud2"
- front_rplidar_obstacle_layer:
+ rplidar_obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
observation_sources: scan
scan:
- topic: /front_2d_lidar/scan
+ topic: /scan
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
- back_rplidar_obstacle_layer:
- plugin: "nav2_costmap_2d::ObstacleLayer"
- enabled: True
- observation_sources: scan
- scan:
- topic: /back_2d_lidar/scan
- max_obstacle_height: 2.0
- clearing: True
- marking: True
- data_type: "LaserScan"
- mapファイルの名称の書き換え
map_server:
ros__parameters:
use_sim_time: True
- yaml_filename: "carter_warehouse_navigation.yaml"
+ yaml_filename: "MCF_navigation.yaml"
を行いました。
6.Navigation
準備が整ったので、いよいよNavigationを実行しましょう。
- IsaacSim起動→シミュレーション再生
- cmdvel_to_ackermann.launch.pyを起動Nav2は
ros2 launch cmdvel_to_ackermann cmdvel_to_ackermann.launch.py acceleration:=0.0 steering_velocity:=0.0
/cmd_vel
を出力しますが、/ackermann
を出力することはできないので、humble_wsに用意されている既存の変換器をかませます。 - RViz起動
ros2 launch carter_navigation MCF_navigation.launch.py
- Nav2 Goalでゴール地点を設定→Navigation開始
![]() |
![]() |
---|
まとめ
本記事では、Isaac Sim 上で MCF のデジタルツインを構築し、Ackermann 型車両(mibot)をナビゲーションさせるまでの手順を紹介しました。
ROS2・Nav2 のセットアップから、URDF 車両モデルへの LiDAR 取り付け、Action Graph の設定、Occupancy Map を用いた地図生成、そしてナビゲーションの実行まで、一通りの流れを体験することができました。
実際に試してみると、設定や依存関係の調整でつまずく部分も多くありましたが、その過程を通じて Isaac Sim の仕組みや ROS2 との連携方法を理解する良い機会になりました。
初心者の記録ではありますが、同じように Isaac Sim を用いて自律走行やデジタルツインに挑戦してみたい方にとって、少しでも参考になれば幸いです。
Discussion