본문 바로가기
Ros 공부/ROS 2 공부

ROS 2 Topic 프로그래밍(Python), 토픽 Publisher Node

by 바위폭주 2025. 3. 6.
728x90
반응형

Topic Publisher Node

ros2_ws/src 디렉터리에 publisher_pkg라는 이름의새 패키지를 만들고 토픽 작업에 필요한 종속성을 추가합니다.

ros2 pkg create --build-type ament_python publisher_pkg --dependencies rclpy std_msgs geometry_msgs
  • 마지막으로 추가된 두 가지 종속성인 std_msgs와 geometry_msgs는 패키지에서 새로 만들 노드에 사용할 인터페이스 입니다.

방금 생성한 패키지의 publisher_pkg 디렉터리에 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):
        super().__init__('simple_publisher')
        self.publisher_ = self.create_publisher(Twist, 'cmd_vel', 10)
        # define the timer period for 0.5 seconds
        timer_period = 0.5
        self.timer = self.create_timer(timer_period, self.timer_callback)

    def timer_callback(self):
        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()

 publihser_pkg_launcy_file.launcy.py라는 런치 파일을 생성하여 방금 생성한 노드를 실행합니다.

cd ~/ros2_ws/src/publisher_pkg
mkdir launch
cd ~/ros2_ws/src/publisher_pkg/launch
touch publisher_pkg_launch_file.launch.py
chmod +x publisher_pkg_launch_file.launch.py

방금 생성한 새 런치 파일에 simple_publisher.py 스크립트의 런치 파일을 시작하는 데 필요한 코드를 작성합니다.

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'),
    ])

 

setup.py를 수정하여 방금 생성한 실행 파일을 설치하고 simple_publisher.py 스크립트의 실행 파일의 entry_points를 추가합니다.

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'
        ],
    },
)

 

패키지를 빌드합니다.

cd ~/ros2_ws
colcon build --symlink-install --packages-select publisher_pkg
source ~/ros2_ws/install/local_setup.bash

 

터미널에서 퍼블리셔 노드를 시작합니다.

ros2 launch publisher_pkg publisher_pkg_launch_file.launch.py

 

0.5초마다 cmd_vel이라는 메세지 형태로 토픽을 Publish하게 됩니다. 토픽을 Subscriber 하고 싶으면

ros2 topic echo /cmd_vel

로 확인하시면 됩니다.

이렇게 토픽을 Publish하는 간단한 파이썬 예제를 다뤄봤는데요, 연습에서는 cmd_vel 메세지 구조에 데이터를 담아서 publish 했습니다. 여기에 원하는 메세지 구조에 원하는 데이터를 담아서 이용하시면 될 것 같습니다. (이미지, 라이다 등등)

728x90
반응형