Hướng dẫn cách tạo một topic publisher trong ROS2 – Vietnamese ROS Tutorial

Written by Tung Ngo

08/03/2024

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 publisher cơ bản trong ROS2 trên nền tảng The Construct.

Nguồn tham khảo

  1. Nền tảng học ROS trực tuyến The Construct
  2. Khóa học ROS2 cơ bản (Python) ROS2 Basics in 5 Days

Tạo một package chứa publisher

Đầu tiên chúng ta sẽ tạo một package có tên là publisher_pkg trong không gian làm việc ros2_ws bằng lệnh sau:

cd ~/ros2_ws/src
ros2 pkg create --build-type ament_python publisher_pkg --dependencies rclpy std_msgs geometry_msgs

Tạo một file publisher

Tiếp theo, chúng ta sẽ tạo một file tên là simple_publisher.py trong thư mục publisher_pkg ở trong package publisher_pkg mà chúng ta vừa tạo. Các bạn lưu ý là file này phải nằm trong thư mục cùng tên nhưng nằm trong package vừa tạo nhé. Cụ thể là đường dẫn tới file simple_publisher.py~/ros2_ws/src/publisher_pkg/publisher_pkg/simple_publisher.py

Tiếp theo, các bạn hãy copy những dòng code sau vào file simple_publisher.py 

import rclpy
# import the ROS2 python libraries
from rclpy.node import Node
# import the Twist interface from the geometry_msgs package
from geometry_msgs.msg import Twist

class SimplePublisher(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_publisher')
        # create the publisher object
        # in this case, the publisher will publish on /cmd_vel Topic with a queue size of 10 messages.
        # use the Twist module for /cmd_vel Topic
        self.publisher_ = self.create_publisher(Twist, 'cmd_vel', 10)
        # define the timer period for 0.5 seconds
        timer_period = 0.5
        # create a timer sending two parameters:
        # - the duration between 2 callbacks (0.5 seconds)
        # - the timer function (timer_callback)
        self.timer = self.create_timer(timer_period, self.timer_callback)

    def timer_callback(self):
        # Here you have the callback method
        # create a Twist message
        msg = Twist()
        # define the linear x-axis velocity of /cmd_vel Topic parameter to 0.5
        msg.linear.x = 0.5
        # define the angular z-axis velocity of /cmd_vel Topic parameter to 0.5
        msg.angular.z = 0.5
        # Publish the message to the Topic
        self.publisher_.publish(msg)
        # Display the message on the console
        self.get_logger().info('Publishing: "%s"' % msg)

def main(args=None):
    # initialize the ROS communication
    rclpy.init(args=args)
    # declare the node constructor
    simple_publisher = SimplePublisher()
    # pause the program execution, waits for a request to kill the node (ctrl+c)
    rclpy.spin(simple_publisher)
    # Explicity destroys the node
    simple_publisher.destroy_node()
    # shutdown the ROS communication
    rclpy.shutdown()

if __name__ == '__main__':
    main()

File simple_publisher.py này chứa nội dung của một topic publisher cơ bản. Hiện tại thì 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 đang làm việc:

cd ~/ros2_ws/src/publisher_pkg
mkdir launch

Tiếp theo, ta sẽ tạo một file launch để chạy node publisher tên là publisher_pkg_launch_file.launch.py

cd ~/ros2_ws/src/publisher_pkg/launch
touch publisher_pkg_launch_file.launch.py
chmod +x publisher_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='publisher_pkg',
            executable='simple_publisher',
            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 = 'publisher_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='user',
    maintainer_email='user@todo.todo',
    description='TODO: Package description',
    license='TODO: License declaration',
    tests_require=['pytest'],
    entry_points={
        'console_scripts': [
            'simple_publisher = publisher_pkg.simple_publisher: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 publisher_pkg
source ~/ros2_ws/install/setup.bash

Chạy publisher node trong Terminal

ros2 launch publisher_pkg publisher_pkg_launch_file.launch.py

Trên Terminal sẽ hiển thị các nội dung message mà node mình vừa tạo đang publish lên topic /cmd_vel. Đồng thời robot cũng bắt đầu di chuyển thành vòng tròn.

Để kiểm tra thông tin đang ở trên topic /cmd_vel, các bạn chạy lệnh :

ros2 topic echo /cmd_vel

Giải thích code tạo publisher

Quy trình hoạt động

def main(args=None):
 # initialize the ROS communication
 rclpy.init(args=args)
 # declare the node constructor
 simple_publisher = SimplePublisher()
 # pause the program execution, waits for a request to kill the node (ctrl+c)
 rclpy.spin(simple_publisher)
 # Explicity destroys the node
 simple_publisher.destroy_node()
 # shutdown the ROS communication
 rclpy.shutdown()

Đầu tiên hệ thống sẽ khởi tạo giao tiếp ROS2 bằng lệnh

rclpy.init(args=args)

Khai báo và khởi tạo node publisher

simple_publisher = SimplePublisher()

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_publisher)

Hủy node

simple_publisher.destroy_node()

Tắt hệ thống giao tiếp ROS2

rclpy.shutdown()

Tạo Class publisher

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_publisher':

super().__init__('simple_publisher')

Tạo một publisher cho topic /cmd_vel sử dụng Twist message với kích thước hàng đợi là 10:

self.publisher_ = self.create_publisher(Twist, 'cmd_vel', 10)

Tạo một timer để kích hoạt hàm timer_callback sau mỗi time_period=0.5

self.timer = self.create_timer(timer_period, self.timer_callback)

Xuất bản nội dung của biến msg lên topic /cmd_vel

self.publisher_.publish(msg)

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 publisher 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.

Video Tutorial

Topics: ros2
Masterclass 2023 batch2 blog banner

Check Out These Related Posts

0 Comments

Submit a Comment

Your email address will not be published.

This site uses Akismet to reduce spam. Learn how your comment data is processed.

Pin It on Pinterest

Share This