This tutorial is created by Robotics Ambassador Tung
Xin chào các bạn! Trong bài viết này mình sẽ hướng dẫn các bạn cách tạo một topic subscriber cơ bản trong ROS2 trên nền tảng The Construct.
Nguồn tham khảo
- Nền tảng học trực tuyến The Construct
- Khóa học ROS2 cơ bản (Python) ROS2 Basics in 5 Days
Tạo một package chứa subscriber
Đầu tiên chúng ta sẽ tạo một package có tên là subscriber_pkg
trong không gian làm việc (VD ros2_ws
) bằng lệnh sau:
cd ~/ros2_ws/src ros2 pkg create --build-type ament_python subscriber_pkg --dependencies rclpy std_msgs sensor_msgs
Nếu các bạn chưa biết cách tạo package trong ros2 như thế nào thì các bạn có thể xem lại video hướng dẫn tạo package của mình trước đây nhé.
Tạo một file subscriber
Tiếp theo, chúng ta sẽ tạo một file tên là simple_subscriber.py
trong thư mục subscriber_pkg
ở trong package subscriber_pkg
mà chúng ta vừa tạo.
Tiếp theo, các bạn hãy copy những dòng code sau vào file simple_subscriber.py
import rclpy # import the ROS2 python libraries from rclpy.node import Node # import the LaserScan module from sensor_msgs interface from sensor_msgs.msg import LaserScan # import Quality of Service library, to set the correct profile and reliability to read sensor data. from rclpy.qos import ReliabilityPolicy, QoSProfile class SimpleSubscriber(Node): def __init__(self): # Here you have the class constructor # call super() in the constructor to initialize the Node object # the parameter you pass is the node name super().__init__('simple_subscriber') # create the subscriber object # in this case, the subscriptor will be subscribed on /scan topic with a queue size of 10 messages. # use the LaserScan module for /scan topic # send the received info to the listener_callback method. self.subscriber = self.create_subscription( LaserScan, '/scan', self.listener_callback, QoSProfile(depth=10, reliability=ReliabilityPolicy.RELIABLE)) # is the most used to read LaserScan data and some sensor data. def listener_callback(self, msg): # print the log info in the terminal self.get_logger().info('I receive: "%s"' % str(msg)) def main(args=None): # initialize the ROS communication rclpy.init(args=args) # declare the node constructor simple_subscriber = SimpleSubscriber() # pause the program execution, waits for a request to kill the node (ctrl+c) rclpy.spin(simple_subscriber) # Explicity destroy the node simple_subscriber.destroy_node() # shutdown the ROS communication rclpy.shutdown() if __name__ == '__main__': main()
File simple_subscriber.py
này chứa nội dung của một node subscriber đơn giản. Các bạn chưa cần hiểu những dòng code này, mình sẽ giải thích ở phần sau. Chúng ta sẽ tiếp tục các bước tiếp theo để chạy thử code xem nó làm được gì trước nhé.
Tạo file launch
Đầu tiên, chúng ta sẽ tạo một thư mục launch
ở trong package subscriber_pkg
đang làm việc bằng lệnh sau:
cd ~/ros2_ws/src/subscriber_pkg mkdir launch
Tiếp theo, ta sẽ tạo một file launch tên là subscriber_pkg_launch_file.launch.py
và chuyển nó sang chế độ executable để chạy node subscriber:
cd ~/ros2_ws/src/subscriber_pkg/launch touch subscriber_pkg_launch_file.launch.py chmod +x subscriber_pkg_launch_file.launch.py
Các bạn copy các dòng code sau vào trong file launch vừa mới tạo:
from launch import LaunchDescription from launch_ros.actions import Node def generate_launch_description(): return LaunchDescription([ Node( package='subscriber_pkg', executable='simple_subscriber', output='screen'), ])
Chỉnh sửa file setup.py
Tiếp theo, các bạn hãy chỉnh sửa file setup.py
để thiết lập các file vừa tạo với hệ thống package:
from setuptools import setup import os from glob import glob package_name = 'subscriber_pkg' setup( name=package_name, version='0.0.0', packages=[package_name], data_files=[ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), (os.path.join('share', package_name), glob('launch/*.launch.py')) ], install_requires=['setuptools'], zip_safe=True, maintainer='somebody very awesome', maintainer_email='user@user.com', description='TODO: Package description', license='TODO: License declaration', tests_require=['pytest'], entry_points={ 'console_scripts': [ 'simple_subscriber = subscriber_pkg.simple_subscriber:main' ], }, )
Biên dịch package
Tiếp theo chúng ta sẽ biên dịch (compile) package bằng các lệnh sau:
cd ~/ros2_ws colcon build --packages-select subscriber_pkg source ~/ros2_ws/install/setup.bash
Chạy subscriber node trong Terminal
Chúng ta sẽ chạy node trong terminal để xem nó làm được gì nhé:
ros2 launch subscriber_pkg subscriber_pkg_launch_file.launch.py
Nếu node hoạt động bình thường thì Terminal sẽ hiển thị nội dung message mà subscriber đọc được.
Giải thích code tạo subscriber
Quy trình hoạt động
def main(args=None):
# initialize the ROS communication
rclpy.init(args=args)
# declare the node constructor
simple_subscriber = SimpleSubscriber()
# pause the program execution, waits for a request to kill the node (ctrl+c)
rclpy.spin(simple_subscriber)
# Explicity destroy the node
simple_subscriber.destroy_node()
# shutdown the ROS communication
rclpy.shutdown()
Đầu tiên, hệ thống sẽ khởi tạo giao tiếp ROS2
rclpy.init(args=args)
Khai báo và khởi tạo node subscriber
simple_subscriber = SimpleSubscriber()
Tạm dừng việc thực thi chương trình, chờ yêu cầu hủy node (ctrl+c)
rclpy.spin(simple_subscriber)
Hủy node
simple_subscriber.destroy_node()
Tắt hệ thống giao tiếp ROS2
rclpy.shutdown()
Tạo class SimpleSubscriber
Phần code này cũng tương tự như khi tạo một class trong python thông thường với hàm khởi tạo __init__
và các hàm chức năng khác. Trong đó quan trọng nhất là các lệnh sau để thực hiện các chức năng liên quan tới ROS:
Khởi tạo một node có tên là 'simple_subscriber'
super().__init__('simple_subscriber')
Phần quan trọng nhất của code là mục tạo subscriber cho topic /scan
sử dụng LaserScan message:
self.subscriber = self.create_subscription(
LaserScan,
'/scan',
self.listener_callback,
QoSProfile(depth=10, reliability=ReliabilityPolicy.RELIABLE))
Ngoài ra, trong lệnh này chúng ta cũng thực hiện hai việc:
- Khai báo hàm callback
self.listener_callback
cho subscriber. Mỗi lần subscriber này đọc được một message mới từ topic/scan
thì hàm callback này sẽ được thực hiện. Hàmself.listener_callback
trong node chúng ta tạo chỉ thực hiện một hành động đơn giản là in nội dung message mà subscriber đọc được ra Terminal. - Định nghĩa QoSProfile – Quality of Service của topic. Hiện tại thì các bạn chưa cần hiểu QoS là gì và chỉ cần biết rằng các thiết lập QoS của topic publisher và subscriber phải phù hợp với nhau. Nếu chúng không phù hợp thì giao tiếp giữa subscriber và puplisher sẽ không hoạt động.
Các bạn có thể xem QoSProfile của topic /scan
bằng lệnh sau:
ros2 topic info /scan -v
Vậy là trong bài viết này mình đã hướng dẫn các bạn cách tạo một topic subscriber cơ bản và các bước chạy thử. Chúc các bạn thực hành thành công.
0 Comments