416 システム/制御/情報,Vol. 61, No. 10, pp. 416–421, 2017 ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
「お隣のアイサイ研究者の
IT
道具箱」特集号
解
説
制御研究者のための
ROS
入門
徳山 享大*・木内 裕介*
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||1.
はじめに
Robot Operating System(ROS)はオープンソースの プロジェクトとして近年急速に台頭したロボット開発の フレームワークである.システム・制御・情報工学を含 む,さまざまな分野の研究者によって膨大なROSのソ フトウエアが公開されており,世界中のユーザによって 共有されている.このような公開ソフトの中には,実際 のセンサやアクチュエータを動作させるためのドライバ 類も多く提供されており,ROSのソフトウエアをうまく 組み合わせるだけで,一定の自律性を備えたロボットを, その日のうちに作り上げることも可能である. 本稿は,ROSをこれから使い始めようとする読者に 対して,入門レベルの解説を行うものである.すでに良 い参考書[1,2]があり,公式Wiki1の解説も充実してい るが,制御工学の研究者がROSのエッセンスを手早く 習得するには,もっと効率的な方法があるように思われ る.そこで本稿では,あまり前置きをせず,ROSを使っ た簡単なフィードバック制御系の作例を具体的に示すア プローチを取る.題材として倒立振子の安定化制御を取 り上げ,ROSおよびROSとの強力な連携機能を有する 3次元動力学シミュレータGazeboを使ってシミュレー タを作る.扱う倒立振子のモデルは,1関節をもつ最も 単純なシリアルリンクのロボットモデルとなる.制御研 究者であれば,本稿の作例を通じて短期にROSのコン セプトをつかみ,その後の応用へ進むことが可能である. 実際,筆者らも初めは簡単なシミュレータを作る過程で ROSへの理解を深めた.本稿の読者にも,それを追体験 してほしいと考えている.ROSを使ったロボット開発の 応用例については,本稿の最後に筆者らの取り組みを紹 介する. 本稿のプログラム作成に使用した PC スペックを 第1表,ROS/Gazeboバージョンを第2 表にまとめる.
1.1
プログラム概要 本稿には,ROSとGazeboのインストール,および ワークスペースの作成2まで完了していることを想定し ∗ 三菱重工業(株) ICTソリューション本部Key Words: robot operating system, Gazebo, robotics.
1http://wiki.ros.org/
2http://wiki.ros.org/ja/ROS/Tutorials/
InstallingandConfiguringROSEnvironment
第1表 PCスペック OS Ubuntu 14.04 LTS (64 bit) CPU Intel Core i5 CPU 760 (2.80GHz× 4)
RAM 12 GB 第2表 ROS/Gazeboバージョン ROS indigo Gazebo 2.2.6 第1図 サンプルプログラム内処理 てプログラム作成手順をまとめる. 作成するサンプルプログラムは第1図に示す分散処理 を行う.ROSで実行するプログラムは,Nodeとよばれ るプロセスが各自の処理を行う分散システムとなってい る.サンプルプログラムでは,「sample load」がロボッ トの角度指令を設定し,それに応じて「sample control」 がフィードバック(FB)制御によりロボットの関節に与 えるトルクを出力する. Node間の通信方法は以下の二つにわけられる. • Publish/Subscribe • Service 一つめの「Publish/Subscribe」は不特定のNode間 でデータのやりとりを行う通信方法である.あるNode があらかじめ決められたデータ型をもつデータをTopic にPublish(出版)する.そのTopicを必要とするNode はTopicをSubscribe(購読)する.この通信は非同期 であり,また,通信相手のNodeを特定しないゆるい通 信方法となっている. 二つめの「Service」は特定のNode間でデータのや りとりを行う通信方法である.あるNodeが提供する Serviceにcallして任意の処理を実行させたり,データ の受け渡しを行う. – 24 –
德
(a)変更前 (b)変更後 第2図 rrbotモデル
2.
ロボットモデルの作成
サンプルモデルには,単純な制御対象として一般的な 単振り子を用いる. より複雑なロボットのモデルをhttp://robots.ros.org /からダウンロードすることもでき,また,ロボットモ デルと併せてプログラムを公開しているサンプルもある ため,本稿の学習後に参考とすることをおすすめする. 単振り子モデルは,Gazeboのチュートリアルにも使 用されている1rrbotを流用して作成する.Ubuntuの ターミナルを起動し,以下のコマンドでrrbotをダウン ロード・ビルドすることでrrbotを入手する. 1 cd ~/ c a t k i n _ w s / src /2 git clone -b indigo - devel https :// github . com / ros - s i m u l a t i o n / g a z e b o _ r o s _ d e m o s . git 3 cd .. 4 c a t k i n _ m a k e rrbotは第2図(a)に示すような二重振り子のロボット モデルである.ロボットモデルを簡易化するため,ロボッ トの構成をxmlで記述するurdfファイルを変更して第 2関節を固定化し,単振り子のロボットモデル(第2 図 (b))を作成する. まず,以下のコマンドでrrbotのurdfファイルを開 く.本稿ではエディタにgeditを使用しているが,Vim やEmacsなど,コーディングに適したエディタを使用 することをおすすめする. 1 roscd r r b o t _ d e s c r i p t i o n / urdf / 2 gedit rrbot . xacro
開いた「rrbot.xacro」を以下のとおり変更し,90行 目をコメントアウト,つぎの行を追加する.
ファイル名: rrbot.xacro
90 <! - - joint name =" joint2 " type =" c o n t i n u o u s " - - >
91 < joint name =" joint2 " type =" fixed " >
ここでは第2関節(joint2)の種類を書き換えており, 1自由度回転するcontinuousジョイントから,自由度0 のfixedジョイントに変更している. ロボットモデルの変更はこれで完了である. 1http://gazebosim.org/tutorials/?tut=ros urdf
3.
ノードの作成
3.1
sample load
の作成 1 s ごとに角度指令を更新してPublish するNode (第1 図中,sample load)を作成する. まずは以下のコマンドで「sample load」パッケージ と実行ファイルを作成する. 1 cd ~/ c a t k i n _ w s / src / 2 c a t k i n _ c r e a t e _ p k g s a m p l e _ l o a d rospy std _ms gs 3 cd s a m p l e _ l o a d 4 mkdir scripts 5 cd scripts 6 gedit s a m p l e _ l o a d . py 上記コマンドの2行目がパッケージのひな形を作成す る箇所であり,作成するパッケージ名「sample load」と 必要なパッケージ「rospy」「std msgs」を指定している. 必要なパッケージを変更する際は,同ディレクトリに自 動作成された「CMakeLists.txt」「package.xml」を変更 する. 作成した「sample load.py」には,以下の通り記述す る.本プログラムは,角度指令を1 sごとに6 deg増加 させてPublishする処理を行う. ファイル名: sample load.py 1 #!/ usr / bin / env python 2 import rospy3 from st d_m sgs . msg import Float64 4 import math 5 6 Ts = 1 7 8 if __n ame __ == ’ __main__ ’: 9 rospy . i n i t _ n o d e ( ’ sample_load ’) 10 rate = rospy . Rate (1.0/ Ts ) 11
12 pub = rospy . P u b l i s h e r ( ’ angle_ref ’ , Float64 , q u e u e _ s i z e =10)
13 ref = 0 14
15 while not rospy . i s _ s h u t d o w n () : 16 pub . publish ( ref )
17
18 ref += ( Ts *2* math . pi /60) 19
20 rate . sleep ()
9行目でNode名(sample load)を宣言し,10行目 でNodeの実行周期(1 Hz)を指定している.12行目 ではPublishするTopic名「angle ref」およびデータ型 (Float64)を指定している. 15行目以降に毎周期実行する処理を記述しており, roscoreが起動している限り実行され続ける.16行目で 角度指令refをPublish,18行目で次サンプルの角度指 令refを計算している.20行目は,10行目で指定した時 間が経過するまで待機する処理である. 作成したプログラムには,以下のコマンドで実行権限 (a)変更前 (b)変更後 第2図 rrbotモデル
2.
ロボットモデルの作成
サンプルモデルには,単純な制御対象として一般的な 単振り子を用いる. より複雑なロボットのモデルをhttp://robots.ros.org /からダウンロードすることもでき,また,ロボットモ デルと併せてプログラムを公開しているサンプルもある ため,本稿の学習後に参考とすることをおすすめする. 単振り子モデルは,Gazeboのチュートリアルにも使 用されている1rrbotを流用して作成する.Ubuntuの ターミナルを起動し,以下のコマンドでrrbotをダウン ロード・ビルドすることでrrbotを入手する. 1 cd ~/ c a t k i n _ w s / src /2 git clone -b indigo - devel https :// github . com / ros - s i m u l a t i o n / g a z e b o _ r o s _ d e m o s . git 3 cd .. 4 c a t k i n _ m a k e rrbotは第2図(a)に示すような二重振り子のロボット モデルである.ロボットモデルを簡易化するため,ロボッ トの構成をxmlで記述するurdfファイルを変更して第 2関節を固定化し,単振り子のロボットモデル(第2 図 (b))を作成する. まず,以下のコマンドでrrbotのurdfファイルを開 く.本稿ではエディタにgeditを使用しているが,Vim やEmacsなど,コーディングに適したエディタを使用 することをおすすめする. 1 roscd r r b o t _ d e s c r i p t i o n / urdf / 2 gedit rrbot . xacro
開いた「rrbot.xacro」を以下のとおり変更し,90行 目をコメントアウト,つぎの行を追加する.
ファイル名: rrbot.xacro
90 <! - - joint name =" joint2 " type =" c o n t i n u o u s " - - >
91 < joint name =" joint2 " type =" fixed " >
ここでは第2関節(joint2)の種類を書き換えており, 1自由度回転するcontinuousジョイントから,自由度0 のfixedジョイントに変更している. ロボットモデルの変更はこれで完了である. 1http://gazebosim.org/tutorials/?tut=ros urdf
3.
ノードの作成
3.1
sample load
の作成 1 s ごとに角度指令を更新してPublishするNode (第1図中,sample load)を作成する. まずは以下のコマンドで「sample load」パッケージ と実行ファイルを作成する. 1 cd ~/ c a t k i n _ w s / src / 2 c a t k i n _ c r e a t e _ p k g s a m p l e _ l o a d rospy std _ms gs 3 cd s a m p l e _ l o a d 4 mkdir scripts 5 cd scripts 6 gedit s a m p l e _ l o a d . py 上記コマンドの2行目がパッケージのひな形を作成す る箇所であり,作成するパッケージ名「sample load」と 必要なパッケージ「rospy」「std msgs」を指定している. 必要なパッケージを変更する際は,同ディレクトリに自 動作成された「CMakeLists.txt」「package.xml」を変更 する. 作成した「sample load.py」には,以下の通り記述す る.本プログラムは,角度指令を1 sごとに6 deg増加 させてPublishする処理を行う. ファイル名: sample load.py 1 #!/ usr / bin / env python 2 import rospy3 from st d_m sgs . msg import Float64 4 import math 5 6 Ts = 1 7 8 if __n ame __ == ’ __main__ ’: 9 rospy . i n i t _ n o d e ( ’ sample_load ’) 10 rate = rospy . Rate (1.0/ Ts ) 11
12 pub = rospy . P u b l i s h e r ( ’ angle_ref ’ , Float64 , q u e u e _ s i z e =10)
13 ref = 0 14
15 while not rospy . i s _ s h u t d o w n () : 16 pub . publish ( ref )
17
18 ref += ( Ts *2* math . pi /60) 19
20 rate . sleep ()
9行目でNode名(sample load)を宣言し,10行目 でNodeの実行周期(1 Hz)を指定している.12行目 ではPublishするTopic名「angle ref」およびデータ型 (Float64)を指定している. 15行目以降に毎周期実行する処理を記述しており, roscoreが起動している限り実行され続ける.16行目で 角度指令refをPublish,18行目で次サンプルの角度指 令refを計算している.20行目は,10行目で指定した時 間が経過するまで待機する処理である. 作成したプログラムには,以下のコマンドで実行権限
418 システム/制御/情報 第61巻 第10号 (2017) を与えること. 1 chmod 755 s a m p l e _ l o a d . py
3.2
sample control
の作成 ロボットモデルの第1関節(joint1)の関節角度をFB 制御するNodeを作成する. 前節同様,まずは以下のコマンドで「sample control」 パッケージと実行ファイルを作成する. 1 cd ~/ c a t k i n _ w s / src / 2 c a t k i n _ c r e a t e _ p k g s a m p l e _ c o n t r o l rospy std _ms gs g a z e b o _ m s g s 3 cd s a m p l e _ c o n t r o l 4 mkdir scripts 5 cd scripts 6 gedit s a m p l e _ c o n t r o l . py 作成した「sample control.py」には,以下の通り記 述する.本プログラムは,Subscribeにより角度指令 (angle ref)を,Serviceによりロボットモデルの現在角 度を取得し,FB制御によるトルク指令を Serviceで joint1に与えることにより,単振り子を任意の角度に制 御する.FB制御系にはPID制御器のみを実装する. ファイル名: sample control.py1 #!/ usr / bin / env python 2 import rospy 3 from g a z e b o _ m s g s . srv import G e t J o i n t P r o p e r t i e s 4 from g a z e b o _ m s g s . srv import A p p l y J o i n t E f f o r t 5 from g a z e b o _ m s g s . srv import J o i n t R e q u e s t 6 from st d_m sgs . msg import Float64
7 import math 8 9 Ts = 0.001 10 j o i n t _ n a m e = ’ joint1 ’ 11 J = 0.58 12 omega = 2* math . pi *2 13 14 def g e t _ r e f _ c a l l b a c k ( data ) : 15 global a n g l e _ r e f 16 a n g l e _ r e f = data . data 17
18 if __ nam e__ == ’ __main__ ’:
19 rospy . i n i t _ n o d e ( ’ sample_control ’) 20 rate = rospy . Rate (1.0/ Ts )
21
22 rospy . S u b s c r i b e r ( ’ angle_ref ’ , Float64 , g e t _ r e f _ c a l l b a c k ) 23 24 g e t _ a n g l e = rospy . S e r v i c e P r o x y ( ’/ gazebo / g e t _ j o i n t _ p r o p e r t i e s ’ , G e t J o i n t P r o p e r t i e s ) 25 c l e a r _ t o r q u e = rospy . S e r v i c e P r o x y ( ’/ gazebo / c l e a r _ j o i n t _ f o r c e s ’ , J o i n t R e q u e s t ) 26 s e t _ t o r q u e = rospy . S e r v i c e P r o x y ( ’/ gazebo / a p p l y _ j o i n t _ e f f o r t ’ , A p p l y J o i n t E f f o r t ) 27 28 Kd = 3* omega **1* J 29 Kp = 3* omega **2* J 30 Ki = 1* omega **3* J 31 32 torque = 0 33 u_z = [0 , 0] 34 y_z = [0 , 0] 35 d_init = True 36 37 a n g l e _ r e f = 0 38
39 while not rospy . i s _ s h u t d o w n () : 40 angle = g e t _ a n g l e ( j o i n t _ n a m e =
j o i n t _ n a m e ) . p osi ti on [0] 41 u_z [0] = a n g l e _ r e f - angle 42 y_z [0] = Ts * sum ( u_z ) /2 + y_z [1] 43
44 if d_init :
45 torque = Kp * u_z [0] + Ki * y_z [0] 46 d_init = False
47 else :
48 torque = Kp * u_z [0] + Ki * y_z [0] + Kd *( u_z [0] - u_z [1]) / Ts 49 50 u_z [1] = u_z [0] 51 y_z [1] = y_z [0] 52 53 c l e a r _ t o r q u e ( j o i n t _ n a m e = j o i n t _ n a m e ) 54 s e t _ t o r q u e ( j o i n t _ n a m e = joint_name ,
effort = torque , du rat ion = rospy . Dur ati on ( -1) )
55
56 rate . sleep ()
18行目以降のメイン関数を解説する.
19行目でNode名(sample control)を宣言し,20行 目でNodeの実行周期(1 kHz)を指定している.22行 目ではSubscribeするTopic名「angle ref」とデータ 型(Float64),コールバック関数名(get ref callback)を 指定している.コールバック関数は指定したTopicが Publishされた際に呼び出される.本プログラムでは 14-16行目がコールバック関数であり,Publishされた Topicをグローバル変数の「angle ref」に代入している.
24行目でService名(gazebo/get joint properties)と 型(GetJointProperties)を指定している.このService は指定したjointの情報を取得するために使用する.
25行目でService名(gazebo/clear joint force)と型 (JointRequest)を指定している.このServiceは指定し たjointのトルクをクリアするために使用する.
26行目でService名(gazebo/apply joint effort)と型 (ApplyJointEffort)を指定している.このServiceは指 定したjointにトルクを与えるために使用する.
39行目以降に毎周期実行する処理を記述しており, roscoreが起動している限り実行され続ける.40行目で Service(gazebo/get joint properties)を使用してjoint1 の角度を取得している.41-51行目でPID制御器の計算 を行い,トルク指令をtorqueに代入している.
53行目でjoint1のトルクをクリアし,54行目でトル – 26 –
ク指令torqueをjoint1に出力する.56行目は,20行目 で指定した時間が経過するまで待機する処理である. 作成したプログラムには,以下のコマンドで実行権限 を与えること. 1 chmod 755 s a m p l e _ c o n t r o l . py 以上でプログラムの作成が完了となる.
最後に,作成したパッケージ(sample load,sample con-trol)をROSのビルドシステムに認識させるために以下 のコマンドを実行する. 1 cd ~/ c a t k i n _ w s / 2 c a t k i n _ m a k e
4.
プログラムの実行
本章には,ここまでに作成したプログラムの実行方法 を記載する. まず,以下のコマンドを実行することで,gazebo上で の単振り子の動作を確認できる. 1 r o s l a u n c h r r b o t _ g a z e b o r r b o t _ w o r l d . launch roslaunchコマンドは,ROSの実行に必須なプロセス roscoreとともに複数のNodeを立ち上げるコマンドであ り,「rrbot gazebo」パッケージ内の「rrbot world.launch」 ファイルをlaunchする. ロボットモデルしか起動していないため,重力によっ て単振り子が振動することが確認できる(第3 図). つぎに,第3.2節で作成したFB制御系を起動するた め,以下のコマンドを実行する. 1 rosrun s a m p l e _ c o n t r o l s a m p l e _ c o n t r o l . py rosrunは単一の実行ファイルを実行するコマンドであ り,「sample control」パッケージ内の「sample control.py」 ファイルを実行している.コマンドを実行すると,FB制御が働いて単振り子が 直立する(0 deg)ことが確認できる(第4 図).これは, 角度指令である「angle ref」TopicがPublishされてい ないことにより,角度指令が初期値0 degに固定されて いるためである. 最後に,第3.1節で作成した角度指令をPublishする Nodeを起動するため,以下のコマンドを実行する. 1 rosrun s a m p l e _ l o a d s a m p l e _ l o a d . py コマンドを実行すると,角度指令が更新され1 sごと に角度が変化していくことが確認できる(第5 図). 本稿で作成したプログラムは簡単なものであるため, これを改良しながらROS/Gazeboの使用方法を学ぶこ とができると考えている.たとえば,制御系を改良した り,角度指令をcsvファイルから読み込んだり,ジョイ スティックと通信するNodeを介して角度指令をリアル 第3図 Gazebo画面1 第4図 Gazebo画面2 第5図 Gazebo画面3 タイム操作したりと,さまざまな改良方法が考えられる. また,rrbotの先端にはカメラが搭載されており,その データを活用するNodeを作成することも可能である. 先述の通り,より複雑なロボットモデルやプログラム をhttp://robots.ros.org/からダウンロードして参考に することも有用である. ROS/Gazeboについてさらに学習したい場合は,参 考文献[1,2]や,ROS/GazeboのHPを参照することを おすすめする.
5.
三菱重工の ROS/Gazebo 活用 [3]
最後に,筆者らがROS/Gazeboの活用に取り組んで いるロボットの例を紹介をする. 三菱重工はさまざまな移動方式をもつ遠隔操作型災 害対応ロボットの開発に関わっており,重大災害発生環 境下での移動能力の向上,および遠隔操作性を向上させ るための環境認識機能の開発において,とくに注力して ROS/Gazeboを活用している. 「MHI-MEISTeRII」は,地形にならうように揺動 可能な四つのクローラで移動する双腕ロボットである (第 6図).傾斜計および荷重・トルクセンサを用いた重 心位置および姿勢の制御により,階段を含むさまざまな 地形を移動できる. 「MHI-Super Giraffe」は,台車で移動し,伸縮はし ご機構でマニピュレータを荷揚げして,8 m高所の作業420 システム/制御/情報 第61巻 第10号 (2017) 第6図 MHI-MEISTeRII[3] 第7図 MHI-Super Giraffe[3] 第8図 WAREC-1[3] 第9図 階段踊り場の通り抜け[3] を可能とするロボットである(第7 図).狭い場所での 機動性向上のため,台車には4輪駆動4輪操舵方式を採 用し,スピン(その場での回転)や真横・斜め方向への 並進が可能である. 「WAREC-1(WAseda REsCuer-No. 1)」は早稲田大 学と共同で開発中の4肢ロボットであり,腹ばい移動や 4足歩行,2足歩行が可能である(第8 図).車輪式やク ローラ式で移動困難な螺旋階段や垂直はしご,着地可能 な領域が限定される離散接地環境に適応しやすい特徴が ある[4]. 移動機能の開発においては,実機試験で万一転倒した 場合にロボットが破損する危険性が高いため,不整地や 階段を模擬した環境を含むGazeboを活用し,実機試験 前に十分な検討を行っている. MHI-MEISTeRIIにおける活用例を第9図に示す.階 段の走行で姿勢の安定性を保つためには,路面との接地 面積ができるだけ広くなるようクローラの寸法・配置を設 計すべきだが,階段途中の狭い踊り場における方向転換 (a)実機 (b) Gazeboモデル 第10図 腹ばい移動[3]
第11図 ros controlを用いたGazeboとROSの連携[3] 時は,クローラ部が大きすぎると旋回できずに行き詰まっ てしまう.この問題への対処として,MHI-MEISTeRII は踊り場を通過するための狭隘路走行姿勢にモード遷移 する機能を有する.姿勢変形による階段踊り場通りぬけ の成立性の確認や,安定的な姿勢移行を実現するための 動作計画の検討にシミュレータを活用している. WAREC-1は螺旋階段や垂直梯子など,車輪式やク ローラ式での移動が難しい環境での運用も想定して開発 中の脚式移動ロボットである.環境に応じて使い分ける 各種移動方式をGazeboによって動力学的に評価できる 環境を構築し,機体開発の効率化を図っている. 腹ばい移動は積極的に胴体を接地させる移動方式であ り,瓦礫が散在して崩れやすい脆弱な環境でも安定して 移動できる.Gazeboを用いて検討したモーションによ り,実機試験での移動も実現している(第10図). 腹ばい移動や垂直梯子移動といった各移動方式の動力 学シミュレーションにおいて,関節への負荷トルクは特 に重視して評価している.WAREC-1では機体製作前に 梯子昇降,腹ばい移動,2足歩行を対象としてGazebo によるシミュレーションを行い,必要トルクの予測結果 を機体設計に反映している[4].
またWAREC-1では,第11図に示すros controlと いうパッケージ1を用いた実機とGazeboの制御ソフト 共有により,効率的なモデルベース開発環境を構築して いる. 遠隔操作型ロボットでは,ロボット周囲の状況をオペ レータに正確かつ直感的に示すことが重要である.ここ 1 http://gazebosim.org/tutorials/?tut=ros control – 28 –
(a)実際の状況 (b) Rvizの表示 第12図 狭隘な空間のマニピュレーション(MHI-Super Giraffe)[3] (a)オドメトリで生成し た地図 (b) SLAMで生成した 地図 第13図 SLAM試験(MHI-MEISTeRII)[3] ではロボット周囲の環境認識技術に関し,レーザスキャ ナを用いた3次元マッピングに関する取り組みを紹介 する. 第 12 図は,Rviz(ROSのビューワ)の3次元地図 を監視しながら狭隘な空間にマニピュレータを侵入させ ている状況である.3次元地図を用いた操作により壁面 までの距離が直感的に把握でき,マニピュレータを安全 に壁面に接近させることができる.結果としてマニピュ レータの作業範囲が拡大し,ロボット運用性が向上する. 第 13 図は,壁面に囲まれた地形で周囲をレーザス キャナで走査しながらMHI-MEISTeRIIが周回走行した ときの地図生成結果であり,同じセンサデータから,オ ドメトリのみで作成した地図と,SLAM(Simultaneous Localization And Mapping)で生成した地図を比較し ている.MHI-MEISTeRIIのようなクローラ式のロボッ トは,滑りながら旋回するためオドメトリによる位置推 定誤差が大きく,第 13図(a)で示す通り地図の歪みが 大きい.一方,SLAMで精度の良い自己位置が得られれ ば,第13図(b)で示す通り地図の歪みを小さくできる. Gazeboはセンサモデルのライブラリが豊富であり,環 境認識系機能の開発にも有用である.実機試験でセンサ の仕様,地形条件,そしてデータ処理方法のパターンを すべて評価することは多大なコストを要するが,Gazebo をうまく活用することで,開発を効率化できる.
6.
おわりに
本稿では,ロボットの機能強化,および開発効率向上 のために近年よく活用されているROS/Gazeboについ て,制御研究者が取り組みはじめやすい単振り子のFB 制御を例として,サンプルモデルの実装方法を記載した. また,最後に三菱重工が開発に関わる災害対応ロボット におけるROS/Gazeboの活用事例を紹介した. 本稿ではROS/Gazeboの機能のごく一部しか紹介で きていないが,ROS初学者の制御研究者が制御系設計 にROS/Gazeboを活用し始めるきっかけとなれば幸い である. 謝 辞本稿のMHI-MEISTeRIIおよびMHI-Super Giraffe に関する内容の一部は,経済産業省の廃炉・汚染水対策 事業費補助金を受け,三菱重工が国際廃炉研究開発機 構(IRID)の一員として行った研究成果を含む.また, WAREC-1に関する内容の一部は,内閣総合科学技術・ イノベーション会議が主導する革新的研究開発推進プロ グラム(ImPACT)「タフ・ロボティクス・チャレンジ」 の研究成果を含む.記して謝意を示す. (2017年7月3日受付) 参 考 文 献 [1] 小倉:ROSではじめるロボットプログラミング,工学社 (2015) [2] 表ら:詳説ROSロボットプログラミング, Kurazume Laboratory (2015) [3] 木内ら: 三菱重工におけるROS/Gazeboを活用したロ ボット;日本ロボット学会誌, Vol. 35, No. 4, pp. 8–11 (2017) [4] 橋本ら:極限条件下で作業可能な災害対応ロボットの開 発(第11報:4肢ロボットWAREC-1の設計と製作); 第34回日本ロボット学会学術講演会, 2C2-02 (2016) 著 者 略 歴 とく 徳 やま山 きょう享 大た 1988年9月24日生.2013年3月東京 大学大学院新領域創成科学研究科先端エ ネルギー工学専攻修士課程修了.同年4月 三菱重工業株式会社入社,現在同社ICT ソリューション本部システム技術開発部 に勤務.機械制御,ロボティクスの研究に 従事. きの 木 うち内 ゆう裕 すけ介 1981年7月7日生.2008年3月京都大 学情報学研究科システム科学専攻修士課程 修了.同年4月三菱重工業株式会社入社, 現在同社ICTソリューション本部システ ム技術開発部に勤務.機械制御,ロボティ クスの研究に従事.計測自動制御学会の会 員.技術士(機械部門). 德