Note: This tutorial assumes that you have completed the previous tutorials: creating a ROS msg and srv.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Viết một Publisher và Subscriber (Python) đơn giản

Description: Hướng dẫn để viết một nút publisher và subscriber trong python.

Tutorial Level: BEGINNER

Next Tutorial: Examining the simple publisher and subscriber

Viết node Publisher

Trong ROS "Node" là một thực thể có thể thực thi và kết nối với mạng lưới ROS. Ở đây chúng ta sẽ tạo một nút publisher ("talker") để có thể phát đi một message.

Thay đổi đường dẫn vào gói beginner_tutorials, bạn đã tạo ra trong hướng dẫn trước, creating a package:

$ roscd beginner_tutorials

The Code

Trước tiên tạo một thư mục 'scripts' để lưu Python scripts:

$ mkdir scripts
$ cd scripts

Sau đó tải ví dụ script talker.py đến thư mục bạn vừa tạo scripts và cấp quyền thực thi cho tập tin:

$ wget https://raw.github.com/ros/ros_tutorials/kinetic-devel/rospy_tutorials/001_talker_listener/talker.py
$ chmod +x talker.py

Bạn có thể xem và chỉnh sửa tập tin với  $ rosed beginner_tutorials talker.py  hoặc chỉ xem qua.

   1 #!/usr/bin/env python
   2 # license removed for brevity
   3 import rospy
   4 from std_msgs.msg import String
   5 
   6 def talker():
   7     pub = rospy.Publisher('chatter', String, queue_size=10)
   8     rospy.init_node('talker', anonymous=True)
   9     rate = rospy.Rate(10) # 10hz
  10     while not rospy.is_shutdown():
  11         hello_str = "hello world %s" % rospy.get_time()
  12         rospy.loginfo(hello_str)
  13         pub.publish(hello_str)
  14         rate.sleep()
  15 
  16 if __name__ == '__main__':
  17     try:
  18         talker()
  19     except rospy.ROSInterruptException:
  20         pass

Diễn giải Code

Bây giờ hãy xem xét từng đoạn mã.

   1 #!/usr/bin/env python

Mỗi Python ROS Node sẽ có khai báo này ở đầu tập tin. Dòng đầu tiên để chắc rằng script sẽ được thực thi như là một Python script.

   3 import rospy
   4 from std_msgs.msg import String

Bạn cần import rospy nếu viết một ROS Node. Định nghĩa message std_msgs.msg cũng cần import như vậy có thể sử dụng lại loại message std_msgs/String (a simple string container) để xuất ra.

   7     pub = rospy.Publisher('chatter', String, queue_size=10)
   8     rospy.init_node('talker', anonymous=True)

Phần mã này sẽ định nghĩa interface talker với phần còn lại của ROS. pub = rospy.Publisher("chatter", String, queue_size=10) khai báo node của bạn sẽ phát đi topic dùng loại meessage String . Ở đây String là một class std_msgs.msg.String. Thông số queue_sizeNew in ROS hydro và giới hạn số lượng message nếu như bất kỳ subscriber không nhận chúng đủ nhanh. Trong phiên bản ROS cũ hơn thì bỏ qua thông số này.

Dòng kế tiếp, rospy.init_node(NAME, ...), rất quan trọng nó khai báo với rospy tên của node -- cho đến khi rospy có thông tin này, nó sẽ không thể bắt đầu giao tiếp ROS Master. Trong trường hợp này, node will take on the name talker. NOTE: tên phải tuân theo base name, i.e. và không chứa ký tự "/".

anonymous = True bảo đảm rằng node có tên riêng biệt bằng cách thêm số ngẫu nhiên tại cuối tên NAME. Tham khảo đến Initialization and Shutdown - Initializing your ROS Node trong tài liệu rospy để có thêm thông tin tùy chọn về khởi tạo node.

   9     rate = rospy.Rate(10) # 10hz

Dòng này tạo ra một đối tượng Rate. Điều này sẽ giúp method sleep(), nó đưa ra tiện ích thiết đặt tầng số cho vòng lặp. Với đối số 10, chúng ta sẽ có 10 lần lặp mỗi giây (cũng như qúa trình xử lý sẽ không vượt qúa 1/10 giây)

  10     while not rospy.is_shutdown():
  11         hello_str = "hello world %s" % rospy.get_time()
  12         rospy.loginfo(hello_str)
  13         pub.publish(hello_str)
  14         rate.sleep()

Qúa trình lặp này là cấu trúc chuẩn trong rospy: kiểm tra cờ rospy.is_shutdown() và tiếp tục thực thi. Bạn cần kiểm tra is_shutdown() để xem nếu chương có thoát không (e.g. if there is a Ctrl-C or otherwise). Trong trường hợp vẫn thực thi , nó sẽ gọi pub.publish(hello_str) để phát đi message string đến topic chatter. Vòng lặp goi rate.sleep(), nó sẽ dừng đủ lâu để bảo đảm duy trì tốc độ thực thi của vòng lặp.

(You may also run across rospy.sleep() which is similar to time.sleep() except that it works with simulated time as well (see Clock).)

Vòng lặp này cũng gọi rospy.loginfo(str), nó sẽ có ba nhiệm vụ: messages nhận sẽ xuất ra màn hình, ghi vào tập tin log của Node, và nó ghi vào rosout. rosout hỗ trợ cho tìm lỗi: Bạn có thể xem messages dùng rqt_console thay cho dùng console window.

std_msgs.msg.String đây là một loại message đơn giản, bạn có thể muốn biết cách xuất message có loại phức tạp. Luật tổng quát như sau cấu trúc đối số thì giống như thứ tự trong tập tin .msg . Bạn cũng có thể khởi tạo trực tiếp mà không có đối số, ví dụ.

msg = String()
msg.data = str

Hoặc bạn có thể khởi tạo một vài trường và để phần còn lại với gía trị mặc định.

String(data=str)

You may be wondering about the last little bit:

  17     try:
  18         talker()
  19     except rospy.ROSInterruptException:
  20         pass

Thêm vào đó theo chuẩn của Python __main__ check, nó sẽ lưu trữ khi lỗi xảy ra rospy.ROSInterruptException, mà có thể từ method rospy.sleep()rospy.Rate.sleep() khi nhấn tổ hợp Ctrl-C hoặc node shutdown. Lý do thông báo exception là bạn sẽ không tiếp tục thực thi code sau khi sleep().

Bây giờ chúng ta sẽ viết node để nhận messages

Viết node Subscriber

The Code

Tải tập tin listener.py vào thư mục scripts:

$ roscd beginner_tutorials/scripts/
$ wget https://raw.github.com/ros/ros_tutorials/kinetic-devel/rospy_tutorials/001_talker_listener/listener.py

Nội dung tập tin:

   1 #!/usr/bin/env python
   2 import rospy
   3 from std_msgs.msg import String
   4 
   5 def callback(data):
   6     rospy.loginfo(rospy.get_caller_id() + "I heard %s", data.data)
   7     
   8 def listener():
   9 
  10     # In ROS, nodes are uniquely named. If two nodes with the same
  11     # node are launched, the previous one is kicked off. The
  12     # anonymous=True flag means that rospy will choose a unique
  13     # name for our 'listener' node so that multiple listeners can
  14     # run simultaneously.
  15     rospy.init_node('listener', anonymous=True)
  16 
  17     rospy.Subscriber("chatter", String, callback)
  18 
  19     # spin() simply keeps python from exiting until this node is stopped
  20     rospy.spin()
  21 
  22 if __name__ == '__main__':
  23     listener()

Đừng quên cấp quyền thực thi:

$ chmod +x listener.py

Diễn giải Code

code cho listener.py thì tương tuwh như talker.py, ngoại trừ có phương thức mới callback-based cho việc đăng ký messages đến.

  15     rospy.init_node('listener', anonymous=True)
  16 
  17     rospy.Subscriber("chatter", String, callback)
  18 
  19     # spin() simply keeps python from exiting until this node is stopped
  20     rospy.spin()

Khai báo này đăng ký topic chatter với loại dữ liệu std_msgs.msgs.String. Khi có messages mới được nhận, callback được gọi với message như đối số đầu tiên.

Thay đổi bằng việc gọi đến rospy.init_node() . Thêm vào từ khóa đối số anonymous=True. ROS yêu cầu rằng mỗi có một tên riêng biệt. Nếu một node với cùng tên dùng tiếp, nó sẽ nhảy đến node trước đó. Điều này cũng sẽ làm node hoạt động không đúng và bị thoát ra khỏi mạng lưới. Cờ anonymous=True thông báo rospy tạo ra một tên không trùng cho node như vậy có thể có nhiều node listener.py chạy.

Cuối cùng, rospy.spin() đơn giản giữ node thực thi từ lúc tạo ra đến khi dừng. Không giống như roscpp, rospy.spin() không tác động đến hàm subscriber callback, do nó có riêng threads.

Building nodes

Chúng ta dùng CMake để build system, và cũng dùng nó cho node Python. Điều này bảo đảm rằng tự động tạo ra Python code cho messages và services.

Chúng ta cũng sẽ dùng Makefile bởi những tiện ích của nó. roscreate-pkg tự động tạo một Makefile, bạn không cần chỉnh sửa nó.

Bây giờ chạy:

$ make

Đi đến thư mục làm việc và chạy catkin_make:

$ cd ~/catkin_ws
$ catkin_make

Now that you have written a simple publisher and subscriber, let's examine the simple publisher and subscriber.

Additional Resources

Here are some additional resources contributed by the community.

Video Tutorial

The following video presents a small tutorial explaining how to write and test a publisher and subscriber in ROS with C++ and Python based on the talker/listener example above

Wiki: vn/ROS/Tutorials/WritingPublisherSubscriber(python) (last edited 2017-08-10 06:33:35 by HoangGiang88)