目的
サービス通信時に必要となるsrvファイルの作成方法について学びます.そして,定義したsrvファイルを使用したサービス通信の実装方法を習得します.C++で実装したい場合にはこちらのページを参照してください.
プログラミングによるサービス通信の実装
プログラムによりサービス通信する方法を習得します.今回は,turtlesimのロボットを回転させるサービスを実装します.
1. パッケージの作成
新たにパッケージを作成しましょう.以前に作成したワークスペース「practice_ws」の中に新しくパッケージ「service_practice」を作成します.依存パッケージとして下記を指定してください.
rospy std_msgs message_generation message_runtime
パッケージの作成方法がわからない人はこちらのページを参照してください.
2. srvファイルの作成
サービス通信は,srvファイルに従ってデータをやり取りします.早速,srvファイルを作成します.まずは,パッケージ内部にsrvファイルを保存するディレクトリを作成し,作成したディレクトリに移動します.
$ cd ~/practice_ws/src/service_practice/ $ mkdir srv $ cd srv
次にsrvディレクトリにsrvファイルを作成します.今回はRotation.srvという名前のファイルを作成し,下記を入力します.
int32 rotation_cnt --- time stamp
前回の講義で学んだ通り,srvファイルは「– – –」よりも上の部分が引数,下の部分が返り値を表しています.
3. CMakeLists.txtの編集
作成したsrvファイルをROSで使用するためにCMakeLists.txtを編集し,ビルドします.まずは,パッケージ内のCMakeLists.txtをエディタで開き,下記のハイライト部分のコメントアウトを解除,及び追加しましょう.
## Generate services in the 'srv' folder add_service_files( FILES Rotation.srv ) ## Generate actions in the 'action' folder # add_action_files( # FILES # Action1.action # Action2.action # ) ## Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES std_msgs )
次に,catkin_makeでビルドします.
yuu@VB:~/practice_ws$ catkin_make Base path: /home/yuu/practice_ws Source space: /home/yuu/practice_ws/src Build space: /home/yuu/practice_ws/build Devel space: /home/yuu/practice_ws/devel Install space: /home/yuu/practice_ws/install #### #### Running command: "cmake /home/yuu/practice_ws/src -DCATKIN_DEVEL_PREFIX=/home/yuu/practice_ws/devel ..." #### -- The C compiler identification is GNU 4.8.4 -- The CXX compiler identification is GNU 4.8.4 -- Check for working C compiler: /usr/bin/cc -- Check for working C compiler: /usr/bin/cc -- works -- Detecting C compiler ABI info -- Detecting C compiler ABI info - done -- Check for working CXX compiler: /usr/bin/c++ -- Check for working CXX compiler: /usr/bin/c++ -- works -- Detecting CXX compiler ABI info -- Detecting CXX compiler ABI info - done -- Using CATKIN_DEVEL_PREFIX: /home/yuu/practice_ws/devel -- Using CMAKE_PREFIX_PATH: /opt/ros/indigo -- This workspace overlays: /opt/ros/indigo -- Found PythonInterp: /usr/bin/python (found version "2.7.6") -- Using PYTHON_EXECUTABLE: /usr/bin/python -- Using Debian Python package layout -- Using empy: /usr/bin/empy -- Using CATKIN_ENABLE_TESTING: ON -- Call enable_testing() -- Using CATKIN_TEST_RESULTS_DIR: /home/yuu/practice_ws/build/test_results -- Looking for include file pthread.h -- Looking for include file pthread.h - found -- Looking for pthread_create -- Looking for pthread_create - not found -- Looking for pthread_create in pthreads -- Looking for pthread_create in pthreads - not found -- Looking for pthread_create in pthread -- Looking for pthread_create in pthread - found -- Found Threads: TRUE -- Found gtest sources under '/usr/src/gtest': gtests will be built -- Using Python nosetests: /usr/bin/nosetests-2.7 -- catkin 0.6.14 -- BUILD_SHARED_LIBS is on -- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -- ~~ traversing 1 packages in topological order: -- ~~ - service_practice -- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -- +++ processing catkin package: 'service_practice' -- ==> add_subdirectory(service_practice) -- Using these message generators: gencpp;genlisp;genpy -- service_practice: 0 messages, 1 services -- Configuring done -- Generating done -- Build files have been written to: /home/yuu/practice_ws/build #### #### Running command: "make -j4 -l4" in "/home/yuu/practice_ws/build" #### Scanning dependencies of target std_msgs_generate_messages_cpp Scanning dependencies of target std_msgs_generate_messages_lisp Scanning dependencies of target std_msgs_generate_messages_py Scanning dependencies of target _service_practice_generate_messages_check_deps_Rotation [ 0%] Built target std_msgs_generate_messages_cpp [ 0%] Built target std_msgs_generate_messages_lisp [ 0%] Built target std_msgs_generate_messages_py [ 0%] Built target _service_practice_generate_messages_check_deps_Rotation Scanning dependencies of target service_practice_generate_messages_lisp Scanning dependencies of target service_practice_generate_messages_py Scanning dependencies of target service_practice_generate_messages_cpp [ 25%] [ 50%] Generating Lisp code from service_practice/Rotation.srv [ 75%] Generating Python code from SRV service_practice/Rotation Generating C++ code from service_practice/Rotation.srv [ 75%] Built target service_practice_generate_messages_lisp [100%] Generating Python srv __init__.py for service_practice [100%] Built target service_practice_generate_messages_py [100%] Built target service_practice_generate_messages_cpp Scanning dependencies of target service_practice_generate_messages [100%] Built target service_practice_generate_messages
ハイライト部分のように出力されると,パッケージでsrvファイルを使えるようになります.最後に,srvファイルをROSで呼び出します.いつも通り,setup.bashをsourceし,作成したsrvファイルを呼び出すことができるか確認します.
$ source devel/setup.bash $ rossrv list | grep service_practice service_practice/Rotation
rossrv listはsrvファイルの一覧を表示しますが,grepを使用してservice_practiceパッケージ内のsrvファイルだけを出力しましょう.上記のように出力されていれば,ROSでRotation.srvを使用できます.
4. プログラムによるサービス通信
サービス通信を実装するためには,サーバとクライアントのプログラムが必要です.
4.1 サーバノード
サーバ側のノードを作成します.「service_practice」の中のscriptsに「turtlesim_rotation_server.py」というファイルを作成し,下記のプログラムを記述します.
#! /usr/bin/env python3 # -*- coding: utf-8 -*- import rospy from geometry_msgs.msg import Twist from service_practice.srv import Rotation class turtleSim: def __init__(self): rospy.init_node('turtlesim_rotation_server', anonymous=True) rospy.loginfo("Ready.") service = rospy.Service('turtlesim_rotation', Rotation, self.rotation) self.twist_pub = rospy.Publisher('turtle1/cmd_vel', Twist, queue_size=1000) twist = Twist() twist.linear.x = 0.0 twist.linear.y = 0.0 twist.linear.z = 0.0 twist.angular.x = 0.0 twist.angular.y = 0.0 twist.angular.z = 0.0 self.twist_pub.publish(twist) def rotation(self, req): twist = Twist() r = rospy.Rate(10) twist.angular.z = 1.0 for i in range(0, req.rotation_cnt): self.twist_pub.publish(twist) r.sleep() now = rospy.get_rostime() return now if __name__ == '__main__': try: ts = turtleSim() rospy.spin() except rospy.ROSInterruptException: pass
トピック通信のプログラムと非常に似ていますので,サービス通信に関する箇所を見ていきます.
#! /usr/bin/env python3 # -*- coding: utf-8 -*- import rospy from geometry_msgs.msg import Twist from service_practice.srv import Rotation
srvファイルをimportしましょう.msgファイルと同様に,「from パッケージ名.srv import サービスファイル名」とします.
class turtleSim: def __init__(self): rospy.init_node('turtlesim_rotation_server', anonymous=True) rospy.loginfo("Ready.") service = rospy.Service('turtlesim_rotation', Rotation, self.rotation) self.twist_pub = rospy.Publisher('turtle1/cmd_vel', Twist, queue_size=1000) twist = Twist() twist.linear.x = 0.0 twist.linear.y = 0.0 twist.linear.z = 0.0 twist.angular.x = 0.0 twist.angular.y = 0.0 twist.angular.z = 0.0 self.twist_pub.publish(twist)
トピック通信のプログラムとほぼ変わりませんが,サービス通信を行うために10行目でturtlesim_rotationというサービスを宣言しています.クライアントノードからturtlesim_rotationというサービスのリクエストがあった場合には,rotation関数が実行されるように設定します.rotation関数が実行されると,turtlesim上のロボットが開店します.
4.2 クライアントノード
クライアント側のノードを作成します.「service_practice」の中のscriptsに「turtlesim_rotation_client.py」というファイルを作成し,下記のプログラムを記述します.
#! /usr/bin/env python3 # -*- coding: utf-8 -*- import rospy from service_practice.srv import Rotation import datetime class turtleSim: ROTATION_CNT = 10 def __init__(self): rospy.init_node('turtlesim_rotation_client', anonymous=True) rospy.wait_for_service('turtlesim_rotation') try: client = rospy.ServiceProxy('turtlesim_rotation', Rotation) req = Rotation() req.rotation_cnt = self.ROTATION_CNT res = client(req.rotation_cnt) rospy.loginfo("Success.time : %i %i", res.stamp.secs, res.stamp.nsecs) except rospy.ServiceException: rospy.loginfo("Fail.") if __name__ == '__main__': try: ts = turtleSim() rospy.spin() except rospy.ROSInterruptException: pass
サーバノードと同様に,サービス通信に関する箇所を見ていきます.
#! /usr/bin/env python3 # -*- coding: utf-8 -*- import rospy from service_practice.srv import Rotation import datetime
クライアントノードにおいても,srvファイルをimportします.
class turtleSim: ROTATION_CNT = 10 def __init__(self): rospy.init_node('turtlesim_rotation_client', anonymous=True) rospy.wait_for_service('turtlesim_rotation') try: client = rospy.ServiceProxy('turtlesim_rotation', Rotation) req = Rotation() req.rotation_cnt = self.ROTATION_CNT res = client(req.rotation_cnt) rospy.loginfo("Success.time : %i %i", res.stamp.secs, res.stamp.nsecs) except rospy.ServiceException, e: rospy.loginfo("Fail.")
13行目でturtlesim_rotationというサービスが使えるようになるまで待機しています.turtlesim_rotationというサービスが利用可能になった場合にはtryの中身が実行されます.15行目ではクライアント側で使用するサービス(turtlesim_rotation)を定義しています.18行目でサービスを呼び出しています.サービスを問題なく呼び出すことができた場合には,Successという単語と共にROS内で使われている時間を表示しています.失敗した場合にはFailという単語を表示します.
5. ビルドと実行
プログラムを入力後,作成したファイルに対して実行権を与えます.
$ chmod u+x turtlesim_rotation_server.py $ chmod u+x turtlesim_rotation_client.py
CMakeLists.txtを編集後,catkin_makeでビルドしてノードを実行します.4つのターミナルを起動し,それぞれのターミナルで下記のようにコマンドを実行します.まずは1つ目のターミナルです.
$ roscore
次に2つ目のターミナルです.
$ rosrun turtlesim turtlesim_node
3つ目のターミナルでは,サーバノードを起動します.
$ cd ~/practice_ws $ source devel/setup.bash $ rosrun service_practice turtlesim_rotation_server.py [ INFO] [1496339523.165127901]: Ready.
4つ目のターミナルでは,クライアントノードを起動します.
$ cd ~/practice_ws $ source devel/setup.bash $ rosrun service_practice turtlesim_rotation_client.py [INFO] [1537307401.995525]: Success.time : 1537307401 994832992
クライアントノードを実行すると,turtlesim上のロボットが回転します.
課題
クライアントノードからロボットのx座標とy座標を送り,サーバノードにて設定した座標を受け取り,その座標に移動するプログラムを実装しなさい.なお,指定した座標への移動は,トピックを購読して得られるロボットの座標及び角度を利用して到達することとする.