Post

ROBOTIS Open Manipulator Xの逆運動学を解くニューラルネットワークIKNet

連載記事

  1. NVIDIA Jetson Nano 2GBプレビューキットのセットアップ
  2. NVIDIA JetPack SDK対応のROS 2 Dockerイメージ作成
  3. NVIDIA Jetson Nano 2GB上でCUDA支援付きROS 2ビデオストリーミング

今回はちょっと趣向を変えて、NVIDIA Jetson Nano 2GB上で4軸マニピュレータROBOTIS Open Manipulator Xの逆運動学を解くという挑戦を行ったレポートを投稿します。

すでに英語版はNVIDIA Developer Forumsに投稿してあるので、それを和訳して、最後に少し考察を加えた内容になります。

https://forums.developer.nvidia.com/t/iknet-inverse-kinematics-neural-networks-for-robotis-open-manipulator-x/165001

IKNet: マニピュレータの逆運動学を解くニューラルネットワーク

IKNetは全結合層だけしかない単純なニューラルネットワークを使ってマニピュレータの逆運動学を解くことができます。 レポジトリには4軸マニピュレータのROBOTIS Open Manipulator Xを手で動かして集めた学習用とテスト用のデータセットも用意されています。

https://github.com/youtalk/iknet-open-manipulator-x

IKNetはNVIDIA Jetson Nano 2GBでも学習ができるように設計しました。もちろん他のJetsonファミリーやPCでも学習できます。 学習スクリプトのデフォルトのオプションだと、900MBのメモリを必要とします。

データ収集

セットアップ

下記e-Manualに従って、ROS 2とROBOTIS Open Manipulator XのパッケージをUbuntu 18.04上にセットアップします。

https://emanual.robotis.com/docs/en/platform/openmanipulator_x/ros2_setup/#ros-setup

このとき、ROBOTIS提供のパッケージだとデータ収集に必要となる open_manipulator_msgs/msg/KinematicsPose メッセージにタイムスタンプがついていないため、タイムスタンプをつけたものを追加でクローンしてビルドする必要があります。

1
2
3
4
5
6
$ mkdir -p ~/ros2/src && cd ~/ros2/src
$ git clone https://github.com/youtalk/open_manipulator.git -b kinematics-pose-header
$ git clone https://github.com/youtalk/open_manipulator_msgs.git -b kinematics-pose-header
$ cd ~/ros2
$ colcon build
$ . install/setup.bash

デモ

最初にOpen Manipulator Xのコントローラを起動します。また、手で動かすためにサーボは切っておきます。

1
$ ros2 launch open_manipulator_x_controller open_manipulator_x_controller.launch.py
1
$ ros2 service call /set_actuator_state open_manipulator_msgs/srv/SetActuatorState

次に、マニピュレータを手でいろんな位置に移動させながら、位置姿勢とそのときの関節角リストを記録していきます。 これには /kinematics_pose/joint_states トピックをCSV形式でros2 topic echoする機能を利用しました。

1
2
$ ros2 topic echo --csv /kinematics_pose > kinematics_pose.csv & \
  ros2 topic echo --csv /joint_states > joint_states.csv

PyTorchのデータセットとして読み込む際に、PandasDataFrameを使うと簡単なため、それに対応するように、CSVファイルに各列の値の内容を書いたヘッダーを追記しておきます。

1
2
$ sed -i "1s/^/sec,nanosec,frame_id,position_x,position_y,position_z,orientation_x,orientation_y,orientation_z,orientation_w,max_accelerations_scaling_factor,max_velocity_scaling_factor,tolerance\n/" kinematics_pose.csv
$ sed -i "1s/^/sec,nanosec,frame_id,name0,name1,name2,name3,name4,position0,position1,position2,position3,position4,velocity0,velocity1,velocity2,velocity3,velocity4,effort0,effort1,effort2,effort3,effort4\n/" joint_states.csv

両者のCSVファイルの行数とタイムスタンプが合うように前後の行をトリムする必要があるかもしれません。

学習

セットアップ

PyTorchと関連するパッケージをインストールします。今回はpytorch-pfn-extrasも使って、ロギングなどの便利機能を使ってみました。

1
2
$ conda install pytorch cudatoolkit=11.0 -c pytorch
$ pip3 install pytorch-pfn-extras matplotlib

デモ

IKNetの学習にはレポジトリの dataset/train ディレクトリに保存された100 [Hz]でサンプリングした5分強のデータセットを使うか、ご自身で用意したものを使ってください。

学習にはEarly Stopping Triggerを使っているため、最大エポック数前に終了する場合があります。

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
$ python3 train_iknet.py --help
usage: train_iknet.py [-h] [--kinematics-pose-csv KINEMATICS_POSE_CSV]
                      [--joint-states-csv JOINT_STATES_CSV] [--train-val-ratio TRAIN_VAL_RATIO]
                      [--batch-size BATCH_SIZE] [--epochs EPOCHS] [--lr LR] [--save-model]

optional arguments:
  -h, --help            show this help message and exit
  --kinematics-pose-csv KINEMATICS_POSE_CSV
  --joint-states-csv JOINT_STATES_CSV
  --train-val-ratio TRAIN_VAL_RATIO
  --batch-size BATCH_SIZE
  --epochs EPOCHS
  --lr LR
  --save-model

$ python3 train_iknet.py
epoch       iteration   train/loss  lr          val/loss
1           3           0.0188889   0.01        0.0130676
2           6           0.0165503   0.01        0.0132546
3           9           0.0167138   0.01        0.0134633
...
61          183         0.00267084  0.01        0.00428417
62          186         0.00266047  0.01        0.00461381
63          189         0.00260262  0.01        0.00461737

学習はNVIDIA Jetson Nano 2GBでも動作します。

ロスには関節角リストのL1ノルムを使いました。最終的なネットワークだと平均0.00461737 [rad]の精度で逆運動学が解けていることを意味します。

train/loss and val/loss

テスト

デモ

IKNetの精度をテスト用データセットで評価することもできます。これにはレポジトリの dataset/test ディレクトリに保存された100 [Hz]でサンプリングした1分強のデータセットを使うか、ご自身で用意したものを使ってください。

1
2
3
4
5
6
7
8
9
10
11
12
$ python3 test_iknet.py --help
usage: test_iknet.py [-h] [--kinematics-pose-csv KINEMATICS_POSE_CSV]
                     [--joint-states-csv JOINT_STATES_CSV] [--batch-size BATCH_SIZE]

optional arguments:
  -h, --help            show this help message and exit
  --kinematics-pose-csv KINEMATICS_POSE_CSV
  --joint-states-csv JOINT_STATES_CSV
  --batch-size BATCH_SIZE

$ python3 test_iknet.py
Total loss = 0.006885118103027344

参考文献

  • Theofanidis, Michail & Sayed, Saif & Cloud, Joe & Brady, James & Makedon, Fillia. (2018). Kinematic Estimation with Neural Networks for Robotic Manipulators: 27th International Conference on Artificial Neural Networks, Rhodes, Greece, October 4–7, 2018, Proceedings, Part III. 10.1007/978-3-030-01424-7_77.
  • Duka, Adrian-Vasile. (2014). Neural Network based Inverse Kinematics Solution for Trajectory Tracking of a Robotic Arm. Procedia Technology. 12. 20–27. 10.1016/j.protcy.2013.12.451.

考察

今回はNVIDIA Jetson Nano 2GBで学習できることを目的としていたため、4軸マニピュレータのデータセットでしか試しておらず、ネットワークのサイズも小さいです。 なので、冗長軸を持つようなロボットにはこのネットワークのままではたぶん対応できません。サイズとデータセットを大きくする必要があります。

また、ランダムな関節角リストとそのときの位置姿勢をデータセットに使うことはやっていません。 これには理由があって、6軸以上あるようなロボットの逆運動学を手で動かしたデータセットから学習すると、特異点回避が簡単にできるのではないかと考えているからです。例えば、真っ直ぐ線を引くような動きをデータセットにたくさん混ぜれば、ロボットでよく起こる特異点周辺で関節がぐるっと回ってしまう問題も演繹的に解決することもできるのではないかと想像しました。これにはフィードバックループのあるネットワークを組まないといけないとは思いますが。

さらに、動いて欲しくない領域をデータセットに含めなければ、自動的に移動領域制限もかけられます。 研究じみてくるので、冬休みの個人課題としては、これくらいで一度終わります。

また、学習はしましたが、それを使って実機で回帰(任意の位置姿勢を入力して関節角を出力する)を行うことはまだやれていません。冬休みは終わってしまいましたが、すぐできるのでいつかやりたいです。

NVIDIA Jetson AI Specialist

このIKNetの成果のおかげで、NVIDIA Jetson AI Specialistにも認定されました。

https://developer.nvidia.com/embedded/learn/jetson-ai-certification-programs

This post is licensed under CC BY 4.0 by the author.

Comments powered by Disqus.