Services (Server-Client)¶
Service merupakan cara lain untuk passsing data antar node dalam ROS. Service memungkinkan salah satu node untuk memanggil sebuah fungsi dari node yang lain. Layanan service itu sendiri di atur oleh server node, yang merupakan tempat dimana callback di panggil. Sedangkan request untuk layanan service di panggil oleh client node.
Berbeda dengan topics, service adalah layanan blocking call, dimana pemrosesan di node tersebut akan terhenti sampai servernya menyelesaikan request dari client. Jadi, services seharusnya tidak digunakan untuk layanan yang memerlukan komputasi yang lama. Salah satu penggunanaan service misalnya untuk melakukan komputasi Inverse Kinematic (IK), inference (object classsification).
Petunjuk
ROS command line tools yang bisa digunakan
rossrv: untuk melihat informasi yang berhubungan dengan srv file definition.
rosservice: untuk melihat dan berinteraksi dengan service tersedia.
Service definition file (srv)¶
srv file memiliki kesamaan struktur seperti msg file. Namun, srv memiliki request dan response. Sebagai contoh, misalnya kita akan membuat service untuk menghitung jumlah kata pada kalimat yang diberikan, maka langkah pertama kita perlu membuat service file CountWords.srv dimana input nya adalah kalimat, dan output nya adalah jumlah kata dalam kalimat tersebut. Request dan response dalam service file di pisahkan dengan ---.
std_msgs/string words
---
std_msgs/Int32 counts
Standar penamaan service file selalu di mulai dengan predikat (verb), misalnya CountWords, RecognizeImage, ComputeIK.
Request juga bisa lebih dari satu message, begitu pula responnya. Misalnya kita mau menambahkan opsi (count_articles) apakah kita mau menghilangkan artikel dalam kalimat tersebut. Sementara di responnya, kita juga bisa menambahkan jumlah artikelnya.
std_msgs/string words
std_msgs/Bool count_articles
---
std_msgs/Int32 num_words
std_msgs/Int32 num_articles
Selanjutnya kita bisa menambahkan CountWords.srv ke CMakeList untuk di compile. Penjelasan lebih lanjut mengenai kompilasinya, di jelaskan disini Kostum messages, srv dan action
Server-Client Python¶
Pertama kita perlu membuat ROS package baru dengan nama rospy_simple_service_server. Jika belum paham tentang paham tentang packages, silahkan buka Membuat ROS Package.
catkin_create_package rospy_simple_service_client rospy ros_custom_msgs
Server (simple_server.py) dan client node (simple_client.py) akan tempatkan di package ini.
Python server node
Sama halnya dengan topic, server di dalam service juga menggunakan mekanisme callback. Server menyediakan callback dan akan di panggil ketika request diterima. Berikut adalah contoh service untuk menghitung jumlah kata menggunakan python dan cpp.
0 #!/usr/bin/env python 1 2 """ 3 This script is a simple python node which advertizes ros service 4 server rospy_word_count 5 """ 6 #-*- encoding: utf-8 -*- 7 __author__ = 'mohammad wasil' 8 9 import rospy 10 from ros_custom_msgs.srv import CountWords, CountWordsResponse 11 12 def server_callback(req): 13 rospy.loginfo("Received request: %s", req.words.data) 14 15 words = req.words.data.split(" ") 16 resp = CountWordsResponse() 17 18 if req.count_articles.data: 19 english_articles = ['a', 'an', 'the'] 20 resp.num_articles.data = len([word for word in words if word in english_articles]) 21 22 resp.num_words.data = len(words) - resp.num_articles.data 23 24 return resp 25 26 if __name__ == '__main__': 27 rospy.init_node("rospy_simple_server_node", anonymous=False) 28 rospy.Service("rospy_word_count", CountWords, server_callback) 29 rospy.spin()
simple_server.py harus executable dengan cara:
chmod +x simple_server.py
Kemudian jalankan node:
rosrun rospy_simple_service_client simple_server.py
Untuk memastikan service server berjalan dengan baik, kita bisa mengeceknya via terminal.
emha at ThinkPad-E570 in ~$ rosservice list /rosout/get_loggers /rosout/set_logger_level /rospy_simple_server_node/get_loggers /rospy_simple_server_node/set_logger_level /rospy_word_countPython client node
0 #!/usr/bin/env python 1 2 """ 3 This script is a simple python node which calls ros service 4 rospy_word_count and send request to the server. 5 """ 6 #-*- encoding: utf-8 -*- 7 __author__ = 'mohammad wasil' 8 9 import rospy 10 from ros_custom_msgs.srv import CountWords, CountWordsRequest 11 12 if __name__ == '__main__': 13 14 #you are not necessarilt inilitialize node 15 #since service client does not have to be a node 16 rospy.init_node("rospy_simple_client_node", anonymous=False) 17 rate = rospy.Rate(10) 18 19 while not rospy.is_shutdown(): 20 rospy.wait_for_service('rospy_word_count') 21 try: 22 word_count = rospy.ServiceProxy('rospy_word_count', CountWords) 23 24 req = CountWordsRequest() 25 req.words.data = "a test from the client node for a simple server client" 26 req.count_articles.data = True 27 28 resp = word_count.call(req) 29 30 rospy.loginfo("Result -> Num of words: %s"%resp.num_words.data) 31 rospy.loginfo("Result -> Num of articles: %s"%resp.num_articles.data) 32 33 except rospy.ServiceException, e: 34 print "Service call failed: %s"%e 35 36 rate.sleep()
Server-Client C++¶
C++ Server node
0 #include <ros/ros.h> 1 #include <ros_custom_msgs/CountWords.h> 2 #include <boost/algorithm/string.hpp> 3 4 bool serverCallback(ros_custom_msgs::CountWordsRequest &req, 5 ros_custom_msgs::CountWordsResponse &resp) 6 { 7 ROS_INFO_STREAM("Request received: "<<req.words.data); 8 9 std::vector<std::string> words; 10 boost::split(words, req.words.data, boost::is_any_of("\t ")); 11 12 resp.num_words.data = words.size(); 13 14 if (req.count_articles.data) 15 { 16 std::vector<std::string> english_articles = {"a", "an", "the"}; 17 int num_of_articles = 0; 18 for (auto const& word: words) 19 { 20 std::string lower_word = boost::algorithm::to_lower_copy(word); 21 if (std::find(english_articles.begin(), english_articles.end(), 22 lower_word ) != english_articles.end()) 23 { 24 num_of_articles ++; 25 } 26 } 27 28 resp.num_articles.data = num_of_articles; 29 resp.num_words.data -= num_of_articles; 30 } 31 return true; 32 } 33 34 int main(int argc, char **argv) 35 { 36 ros::init(argc, argv, "roscpp_simple_server_node"); 37 ros::NodeHandle nh; 38 ros::ServiceServer service = nh.advertiseService("roscpp_word_count", serverCallback); 39 ros::spin(); 40 41 return 0; 42 }
C++ Client node
0 #include <ros/ros.h> 1 #include <ros_custom_msgs/CountWords.h> 2 3 int main (int argc, char **argv) 4 { 5 ros::init(argc, argv, "roscpp_simple_client_node"); 6 ros::NodeHandle nh; 7 ros::ServiceClient service_client = nh.serviceClient<ros_custom_msgs::CountWords>("roscpp_word_count"); 8 ros::Rate loop_rate(10); 9 while(ros::ok()) 10 { 11 ros_custom_msgs::CountWords srv; 12 srv.request.words.data = "A sample request from a client for a simple service client test"; 13 srv.request.count_articles.data = true; 14 15 if (service_client.call(srv)) 16 { 17 ROS_INFO_STREAM("Result -> Num of words: "<<srv.response.num_words.data); 18 ROS_INFO_STREAM("Result -> Num of articles: "<<srv.response.num_articles.data); 19 } 20 else 21 { 22 ROS_ERROR("Failed to call the service server"); 23 } 24 25 loop_rate.sleep(); 26 } 27 return 0; 28 }
Contoh CMakeList.txt
0 cmake_minimum_required(VERSION 2.8.3) 1 project(roscpp_simple_service_client) 2 3 ## Compile as C++11, supported in ROS Kinetic and newer 4 add_compile_options(-std=c++11) 5 6 find_package(catkin REQUIRED COMPONENTS 7 ros_custom_msgs 8 roscpp 9 ) 10 11 catkin_package( 12 ) 13 14 include_directories( 15 # include 16 ${catkin_INCLUDE_DIRS} 17 ) 18 19 #Executable 20 add_executable(simple_server 21 ros/src/simple_server.cpp 22 ) 23 add_dependencies(simple_server 24 ${catkin_EXPORTED_TARGETS} 25 ) 26 target_link_libraries(simple_server 27 ${catkin_LIBRARIES} 28 ) 29 30 add_executable(simple_client 31 ros/src/simple_client.cpp 32 ) 33 add_dependencies(simple_client 34 ${catkin_EXPORTED_TARGETS} 35 ) 36 target_link_libraries(simple_client 37 ${catkin_LIBRARIES} 38 )