目的
サービス通信時に必要となるsrvファイルの作成方法について学びます.そして,定義したsrvファイルを使用したサービス通信の実装方法を習得します.pythonで実装したい場合にはこちらのページを参照してください.
プログラミングによる配信と購読
プログラムによりサービス通信する方法を習得します.今回は,turtlesimのロボットを回転させるサービスを実装します.
1. パッケージの作成
新たにパッケージを作成しましょう.以前に作成したワークスペース「practice_ws」の中に新しくパッケージ「service_practice」を作成します.依存パッケージとして下記を指定してください.
roscpp 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ファイルを使えるようになります.正常にビルドできている場合は,「~/practice_ws/devel/include/service_practice」の中にヘッダーファイルが生成されています.ヘッダーファイルが生成されていない場合は,CMakeLists.txtを正しく編集できているか確認しましょう.
最後に,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」の中のsrcに「turtlesim_rotation_server.cpp」というファイルを作成し,下記のプログラムを記述します.
#include "ros/ros.h" #include "geometry_msgs/Twist.h" #include "service_practice/Rotation.h" class turtleSim{ public: turtleSim(); ~turtleSim(); bool rotation(service_practice::Rotation::Request &req, service_practice::Rotation::Response &res); private: ros::Publisher twist_pub; ros::NodeHandle nh; ros::ServiceServer service; }; turtleSim::turtleSim(){ service = nh.advertiseService("turtlesim_rotation", &turtleSim::rotation, this); twist_pub = nh.advertise<geometry_msgs::Twist>("turtle1/cmd_vel", 1000); geometry_msgs::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; twist_pub.publish(twist); } turtleSim::~turtleSim(){ } bool turtleSim::rotation(service_practice::Rotation::Request &req, service_practice::Rotation::Response &res){ geometry_msgs::Twist twist; int i; ros::Rate loop_rate(10); for(i = 0;i < req.rotation_cnt; i++){ twist.angular.z = 1.0; twist_pub.publish(twist); loop_rate.sleep(); } return true; } int main(int argc, char **argv){ ros::init(argc, argv, "turtlesim_rotation_server"); turtleSim turtlesim; ROS_INFO("Ready."); ros::spin(); return 0; }
トピック通信のプログラムと非常に似ていますので,サービス通信に関する箇所を見ていきます.
#include "ros/ros.h" #include "geometry_msgs/Twist.h" #include "service_practice/Rotation.h"
srvファイルを作成してcatkin_makeするとヘッダーファイルが生成されます.プログラムでサービス通信を実現する際には,生成したヘッダーファイルを読み込む必要があります.今回はservice_practiceという名前のディレクトリに生成されるRotation.hを読み込みます.
class turtleSim{ public: turtleSim(); ~turtleSim(); bool rotation(service_practice::Rotation::Request &req, service_practice::Rotation::Response &res); private: ros::Publisher twist_pub; ros::NodeHandle nh; ros::ServiceServer service; };
トピック通信のプログラムとほぼ変わりませんが,サービス通信を行うためにコールバック関数rotationを定義しています.引数にはリクエストの変数名とレスポンスの変数名を与えます.書式が複雑ですが,パッケージ名::srvファイル名(.srvの拡張子は必要ありません)::リクエストもしくはレスポンスとなります.
turtleSim::turtleSim(){ service = nh.advertiseService("turtlesim_rotation", &turtleSim::rotation, this); twist_pub = nh.advertise<geometry_msgs::Twist>("turtle1/cmd_vel", 1000); geometry_msgs::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; twist_pub.publish(twist); }
こちらもトピック通信のプログラムとほぼ同じです.異なる点は19行目のサービス通信のためのコールバック関数の宣言です.クライアントノードからturtlesim_rotationというサービスのリクエストがあった場合には,rotation関数が実行されるように設定します.
4.2 クライアントノード
クライアント側のノードを作成します.「service_practice」の中のsrcに「turtlesim_rotation_client.cpp」というファイルを作成し,下記のプログラムを記述します.
#include "ros/ros.h" #include "service_practice/Rotation.h" #define ROTATION_CNT 10 class turtleSim{ public: turtleSim(); ~turtleSim(); private: ros::NodeHandle nh; service_practice::Rotation::Request req; service_practice::Rotation::Response res; ros::ServiceClient client; }; turtleSim::turtleSim(){ client = nh.serviceClient<service_practice::Rotation>("turtlesim_rotation", this); req.rotation_cnt = ROTATION_CNT; if(client.call(req, res)){ ROS_INFO("Success."); }else{ ROS_INFO("Fail."); } } turtleSim::~turtleSim(){ } int main(int argc, char **argv){ ros::init(argc, argv, "turtlesim_rotation_client"); turtleSim turtlesim; return 0; }
サーバノードと同様に,サービス通信に関する箇所を見ていきます.
#include "ros/ros.h" #include "service_practice/Rotation.h"
クライアントノードにおいても,生成したヘッダーファイルを読み込む必要があります.service_practiceという名前のディレクトリに生成されるRotation.hを読み込みます.
#define ROTATION_CNT 10
リクエスト時に送る値をプリプロセッサ指令により定義しています.
turtleSim::turtleSim(){ client = nh.serviceClient<service_practice::Rotation>("turtlesim_rotation", this); req.rotation_cnt = ROTATION_CNT; if(client.call(req, res)){ ROS_INFO("Success."); }else{ ROS_INFO("Fail."); } }
19行目で利用するサービスの型(service_practice::Rotation)に合わせ,クライアント側で使用するサービス(turtlesim_rotation)を定義しています.
21行目では,リクエストで送る変数に値を代入しています.リクエスト及びレスポンスで扱える変数は,srvファイルによって定義されます.
22行目ではclient.call関数によってサービスを呼び出しています.返り値がtrueの場合には受け取り成功,falseの場合には受け取り失敗となります.
5. ビルドと実行
プログラムを入力後,パッケージ内のCMakeLists.txtの最後に下記を追加します.
add_executable(turtlesim_rotation_server src/turtlesim_rotation_server.cpp) target_link_libraries(turtlesim_rotation_server ${catkin_LIBRARIES}) add_dependencies(turtlesim_rotation_server service_practice_gencpp) add_executable(turtlesim_rotation_client src/turtlesim_rotation_client.cpp) target_link_libraries(turtlesim_rotation_client ${catkin_LIBRARIES}) add_dependencies(turtlesim_rotation_client service_practice_gencpp)
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 [ INFO] [1496339523.165127901]: Ready.
4つ目のターミナルでは,クライアントノードを起動します.
$ cd ~/practice_ws $ source devel/setup.bash $ rosrun service_practice turtlesim_rotation_client [ INFO] [1496339568.758684320]: Success.
クライアントノードを実行すると,turtlesim上のロボットが回転します.
課題
1. 「turtlesim_rotation_client.cpp」の4行目で定義されているROTATION_CNTの値を変更し,実行した際の挙動の変化を確認しなさい.
2. 「turtlesim_rotation_client.cpp」の4行目で定義されているROTATION_CNTの値を100に変更し,ロボットが回転している間にrosnode listで起動しているノードを確認しなさい.
3. 上記のサービス通信のプログラムとsrvファイルを改良し,turtlesim上のロボットを前進しながら回転するプログラムを作成しなさい.
加点課題
1. 上記のサービス通信のプログラムを改良し,クライアントノードで座標(x,y)をリクエスト,サーバノードで受け取った座標にロボットを移動させなさい.