eSEATでROSノードを作る(Service)
Simple Wiki Based Contents Management System
ソフトウェア関連 >> RTコンポーネント関連 >> eSEAT_v2.5 >> SEATMLファイルの書き方 >> ROSノードの作成(eSEAT) >> eSEATでROSノードを作る(Service)

eSEATでROSノードを作る(Service)

ROSのPub/Subインターフェースの次にサービスへの対応について説明していきます。ROSにおけるサービスは、RTCにおけるサービスポートとeSEAT内の実装がよく似ています。また、ROSのサービスにも同期、非同期の呼び出しがあったり、actionlib等の実装もありますが、今のところeSEATにおけるサービスのサポートは、同期型のサービスのみです。
ここでもROSのチュートリアルに従って add_two_intsサービスのサーバーとクライアントのSEATMLファイルを作成していきます。このサービスは、初心者チューとリアルでは、beginer_tutorialsというパッケージで2つの整数を受け取り、合計を返すものです。
ROSチュートリアルでは、独自のパッケージを作成してサービスの実装を行っていましたが、ここでもPub/Subのときと同じように、''~/ros_ws'' を作業ディレクトリにしていきます。

サーバーの実装

まずは、Publisher/Subscriberの作成のときと同様にひな形をadd_two_ints_server.seatmlとしてコピーします。
 # cd ~/ros_ws
 # source /usr/local/eSEAT/setup.bash
 # gen_seatml add_two_ints_server
ROSサーバーのみであれば、動作周波数を入力する必要はありません。
 <?xml version="1.0" encoding="UTF-8" ?>
 <seatml>
  <general name="add_two_ints_server" >
  </general>

  <state name="main_state">
 </state>
 </seatml>
次にROSサービス・サーバーのadaptorの定義を行います。eSEATにおけるROSサービスのadaptorは、ros_serverとros_clientで作成し、<adaptor>要素の属性は、下記のようになっています。
属性説明
type'ros_server'(サーバー)または 'ros_client'(クライアント)のどちらかの値
nameRosのサービス名または識別子、Rosサービス名の場合には、識別子は、''Rosサービス名+'_'+ type'''に変換される
serviceRosのサービス名
service_typeRosのサービスタイプ
impl'ros_server'の場合にサービスが実装された関数名を指定します
file'ros_server'の場合に、インポートしたい外部Pythonプログラムファイル(file_exec関数で実行します)
ROSサービス・サーバーの場合には、type属性として''ros_server''を指定します。また、ros_serverアダプタの生成時に rospy.Service関数を呼び出して、サービスを定義しますので、サービス関数の実装を予め定義しておく必要があります。
RTCのサービスポートの時と同様に、サービス関数の実装には、外部ファイルで定義しておく方法とSEATMLの<script>要素で定義する方法があります。
ここでは、<scritp>要素で行いますが、サービス関数を'handle_add_two_ints' として、サービス名を'add_two_ints',サービスタイプを 'beginner_tutorials.AddTwoInts'とすると、adaptorは下のように定義することができます。
 <adaptor name="add_two_ints" type="ros_server"
          impl="handle_add_two_ints" service_type="beginner_tutorials.AddTwoInts" />
このサービスの定義は敢えてROSのチュートリアルと同じにしています。
あとは、サービス関数の実装とサービスタイプの定義が必要です。ROSチュートリアルでは、beginner_tutorialsというパッケージを作成して、AddTwoInts.srvというサービスを定義していました。既に、beginner_tutorialsを作成してあれば、setup.bashを読み込んでおけば終わりなのですが、ここでは現在の作業ディレクトリにサービス定義を作成していきます。
eSEATをinstall.shスクリプトでインストールした場合には、/usr/local/eSEAT/binに gen_ros_pkgとgen_ros_msgのコマンドがインストールされています。ここでは、独自サービスになりますので、このコマンドを使います。
まず、AddTwoInts.srvを作成するために、beginner_tutorialsという名前のパッケージ用のディレクトリを作成します。
 # cd ~/ros_ws
 # gen_ros_pkg beginner_tutorials
これで、 ~/ros_ws/ros/lib/site-packages, ~/ros_ws/ros/packages/beginner_tutorials/msg, ~/ros_ws/ros/packages/beginner_tutorials/srv が生成されていると思います。
次に、ROSチュートリアルと同じように rospy_tutorials のAddTwoInts.srvを~/ros_ws/ros/packages/beginner_tutorials/srvにコピーします。
 # source /opt/ros/kinetic/setup.bash
 # roscp rospy_tutorials srv/AddTwoInts.srv ros/packages/beginner_tutorials/srv
AddTwoInts.srv がコピーされれば、このファイルをサービスタイプとしてimportできるようにコンパイルします。コンパイルには、gen_ros_msgを使います。
 # source /opt/ros/kinetic/setup.bash
 # cd ~/ros_ws
 # gen_ros_msg
以上でサービスファイルのコンパイルが終了し、~/ros_ws/ros/lib/site-packages/beginner_tutorials が生成されていると思います。
最後に、サービス関数を定義します。ROSチュートリアルでは、'handle_add_two_ints関数'は、下のようになっていました。
 def handle_add_two_ints(req):
    print "Returning [%s + %s = %s]"%(req.a, req.b, (req.a + req.b))
    return AddTwoIntsResponse(req.a + req.b)
しかし、SEATMLでは、サービス関数からの返り値を eSEATの内部でXXXResponse関数に引き渡していますので、下のようになります。
    <script>
      def handle_add_two_ints(req):
        res = req.a+req.b
        print ("Returning [ %s + %s = %s]" % (req.a, req.b, res))
        return res
    </script>
以上でROSサーバーの実装は完了です。

サービスの内容を rule要素で書く

上記の例では、サービスを予め関数で定義する方法を示しました。現在(2018-11-19)には、<state>要素の下の<rule>要素でもサービスを定義できるようになっています。aサービスを<rule>要素で定義する場合には、adaptor要素でimpl属性を指定せずに、下のように変更する必要があります。
 <adaptor name="add_two_ints" type="ros_server" service_type="beginner_tutorials.AddTwoInts" />
次に、サービスの定義ですが、下のように<rule>要素にsource属性で、adaptorのname属性(サービス名)を指定し、<key>要素を ros_service で追加する必要があります。これは eSEATの内部で<key>要素とsource属性でマッチングを行っているからです。
  <rule source="add_two_ints">
    <key>ros_service</key>
    <script>
        req=seat.get_in_data()[0]
        res = req.a+req.b
        print ("Returning [ %s + %s = %s]" % (req.a, req.b, res))
        seat.set_result( res )
    </script>
  </rule>
ここで気を付けなければいけないのは、eSEATの<script>要素に記載したPythonコードは、exec関数で実行しているために、return文などが使用できないことです。
また、サービスに対する引数も少し特殊な扱いをしなければいけません。

eSEATの内部では、script要素に渡す引数データは、seat_argvという変数にtupple形式のデータで代入されています。
そのため上記のように、''req=seat.get_in_data()[0]'' または ''req=seat_argv[0]'' として引数データを受け取ります。

また、結果の出力には、return文が使えませんので、''seat.get_result''メソッドを呼び出すか、 ''rtc_result''という変数に代入して終了してください。

クライアントの実装

次に、クライアントの実装を行います。最初は、サーバーのときと同じように、ひな形をadd_two_ints_client.seatmlにコピーします。
 # cd ~/ros_ws
 # source /usr/local/eSEAT/setup.bash
 # gen_seatml add_two_ints_client
こちらも周期実行する部分は対話的なユーザインターフェースになりますので、動作周波数を入力する必要はありません。
 <?xml version="1.0" encoding="UTF-8" ?>
 <seatml>
  <general name="add_two_ints_client" >
  </general>

  <state name="main_state">
 </state>
 </seatml>
次に、ros_clientのadptorを定義します。サービス名とサービスタイプは、サーバーと同じですので
    <adaptor name="add_two_ints" type="ros_client"
             service_type="beginner_tutorials.AddTwoInts" />
となります。
残るは、クライアントのコンソールから2つの整数を代入するし、答えを出力するユーザインターフェース部分の実装です。
RTCのConsumerと同じように<onexec>要素に<script>要素で定義していきます。
 <onexec>
   <script>
    print("\n")
    print("Input 2 ints> ", end="", flush=True)
    args = str(sys.stdin.readline())
    argv = args.split()
    argv[-1] = argv[-1].rstrip("\n")

    if len(argv) > 1:
      a=int(argv[0])
      b=int(argv[1])
      retval=seat.callRosService("add_two_ints", a, b)
      print(a, "+", b, "=", retval.sum)
    else:
      pass
   </script>
 </onexec>
eSEATでは、ROSサービスの呼出しには、seat.callRosServiceを使います。第1引数は、サービス名であり、第2引数以降は、サービスタイプで定義された引数になります。返り値は、Response型になりますので、ここではretval.sumになります。
以上でクライアントのSEATMLファイルの作成は終了です。

ROSサービスの動作確認

ROSサービスのサーバーとクライアントができましたので、動作確認を行います。ROSノードを起動する場合には、Pub/Subの場合と同様にroscoreが必要になります。
ターミナルを3つ起動し、下のようにコマンドを入力します。
  • ターミナル1(roscore)
 # . /opt/ros/kinetic/setup.bash
 # roscore
  • ターミナル2(server)
 # . /opt/ros/kinetic/setup.bash
 # cd ~/ros_ws
 # eSEAT_Node add_two_ints_server.seatml
  • ターミナル3(client)
 # . /opt/ros/kinetic/setup.bash
 # cd ~/ros_ws
 # SEAT_Node add_two_ints_client.seatml
すべてのモジュールの起動が確認できれば、ターミナル3で2つの整数の入力を行い、サービスの動作を確認してください。

GUI付きのクライアントに改変する

上の例では、ROSサービス・クライアントはCUIでしたが、eSEATでは簡易GUI作成機能もありますので、GUIアプリケーション化を行いたいと思います。
実装するものは、下記のように2つの整数の入力用のENTRYと結果出力のTEXTにします。

GUIの部分のデザインは、下のとおりになります。
 <label text="Add two ints" colspan="5" bg_color="blue" /><brk />

 <label text="Input:" /><input id="a1" width="5" /><label text=" +" /> <input id="a2" width="5" />
 <button label="Send"></button><brk />

 <label text="Answer:" />
 <text id="ans" width="50" height="5" colspan="4" >
 </text><brk />

 <button label="Clear"></button>
次に、SendボタンとClearボタンにそれぞれアクションを実装します。Sendボタンには、a1とa2の値を取得して、add_two_intsサービスの呼び出し、ClearボタンはansTEXTの内容の消去です。
Sendボタンは、
 <script>
   a1 = seat.getEntry("main_state:a1")
   a2 = seat.getEntry("main_state:a2")
   retval=seat.callRosService("add_two_ints", int(a1), int(a2))
   str_out=a1+" + "+a2+" = "+str(retval.sum)
   seat.appendText("main_state:ans", str_out + "\n")
   print (str_out)
 </script>
となり、Clearボタンは、
 <script>
   seat.clearText("main_state:ans")
 </script>
となります。
最終的なSEATMLファイルは、下のとおりです。
<?xml version="1.0" encoding="UTF-8"?>
<seatml>
  <general name="RosClient" anonymous="1">
    <adaptor name="add_two_ints" type="ros_client"
             service_type="beginner_tutorials.AddTwoInts" />
  </general>

  <state name="main_state">
    <label text="Add two ints" colspan="5" bg_color="blue" />
    <brk />
    <label text="Input:" />
    <input id="a1" width="5" ></input>
    <label text=" +" />
    <input id="a2" width="5" ></input>
    <button label="Send">
      <script>
       a1 = seat.getEntry("main_state:a1")
       a2 = seat.getEntry("main_state:a2")
       retval=seat.callRosService("add_two_ints", int(a1), int(a2))
       str_out=a1+" + "+a2+" = "+str(retval.sum)
       seat.appendText("main_state:ans", str_out + "\n")
       print (str_out)
      </script>
    </button>
    <brk />
    <label text="Answer:" />
    <text id="ans" width="50" height="5" colspan="4" >
    </text>
    <brk />
    <button label="Clear">
      <script>
       seat.clearText("main_state:ans")
      </script>
    </button>
  </state>
</seatml>

ROS2で動作させるために

上記の例は、すべてROSでの実装例でしたが、eSEATではROS2も同じようにサービスを実行することができます。ROS2のサービス実装とROS1のサービス実装の最も大きな相違点は、サービス関数の引数が異なることです。(正確には、サービス呼び出し部分も異なるのですが、eSEATへの対応としては、サービス関数の部分が一番大きいと思います)
上記のサービス関数をROS2でも動作するように、下のように改変します。
    <script>
      def handle_add_two_ints(req, res=None):
        sum_val = req.a+req.b
        print ("Returning [ %s + %s = %s]" % (req.a, req.b, sum_val))

        if res: res.sum = sum_val
        else: res = sum_val

        return res
    </script>
この改変でもわかるように、ROS2のサービス関数では、返り値となるresを引数として渡します。したがって、上記のようにサービス関数を定義しておけば、ROS1でもROS2でも改変なしで動作させることができます。

eSEATのROS2対応の未実装部分

eSEATのROS2対応に関して、ROS1の時のように独自メッセージ型やサービスタイプのコンパイルに関しては、未実装のままです。まだ、ROS2の普及がイマイチの状況であるのと、ROS2はまだこれからも大きな変化があるように思えますので、ROS2への対応に関しては、しばらくこのままである可能性が高いです。ご了承下さい。
したがって、独自メッセージ型や独自のサービスを作成したい場合には、まず、ROS2の開発環境で作成して下さい。
ここでは、rospy_tutorialsに AddTwoIntsサービスがありますので、SEATMLファイルをservice_typeのパケージ名をrospy_tutorialsに変更すれば、動作確認をすることができます。
上記の add_two_ints_server.seatml内の adaptor定義を
 <adaptor name="add_two_ints" type="ros_server"
          impl="handle_add_two_ints" service_type="rospy_tutorials.AddTwoInts" />
に変更し、add_two_ints_client.seatmlのadaptor定義を
 <adaptor name="add_two_ints" type="ros_client" service_type="rospy_tutorials.AddTwoInts" />
に変更して下さい。次に、ROS2の動作確認を行います。
ROS2における動作確認は、2つのターミナルで行います。
  • ターミナル1(talker)
 # . /opt/ros/ardent/setup.bash
 # cd ~/ros_ws
 # eSEAT_Node3 add_two_ints_server.seatml
  • ターミナル2(listener)
 # . /opt/ros/ardent/setup.bash
 # cd ~/ros_ws
 # eSEAT_Node3 add_two_ints_client.seatml
これでROSの時と同様に、ターミナル2から2つの整数を入力すれば、その和が返されると思います。