본문 바로가기
ros2_python/Ros2 msg,srv,action,parm

ros2_msg 토픽 example(executor사용==멀티쓰레드)

by 알 수 없는 사용자 2022. 7. 5.

멀티스레드 사용해서 ROS2 SUBSCRIBE

예제

# ===========================================================================================
# !/usr/bin/python
# -*- coding: utf-8 -*-
import rclpy
from rclpy.executors import Executor  # noqa: F401
from rclpy.qos import QoSProfile
import threading
import time
from std_msgs.msg import String

class Ros2SubNodeAgent:
    """
    멀티 쓰레드 에 멀티 노드 구조
    멀티쓰레딩 subscribe 내용을 참조 사이트
    https://answers.ros.org/question/377848/spinni_sigint_gcng-multiple-nodes-across-multiple-threads/
    """

    def __init__(self, _module_info):
        """
        """
        self._executor = None
        self._module_info = _module_info
        self._qos_profile = QoSProfile(depth=10)
        self._node_obj = None

    def set_up_sub(self):
        print(self, ' : setup stat')
        self._create_node()
        self._node_obj_create_subscription()
        print(self, ' : setup end')

    def _create_node(self) -> None:
        """
        node object 생성
        """
        if rclpy.ok():
            pass
        else:
            rclpy.init()

        _node_name = self._module_info['node_info']['node_name']
        self._node_obj = rclpy.create_node(_node_name)
    def _node_obj_create_subscription(self) -> None:
        """
        executor에 등록된 node_obj에 type,topic_name,콜백함수,qos 정보 삽입
        """
        self._node_obj.subscription = self._node_obj.create_subscription(
            self._module_info['node_info']['msg_type'],
            self._module_info['node_info']['topic_name'],
            self._module_info['node_info']['callback_func'],
            self._qos_profile)

    def get_node_obj_id(self):
        return self._node_obj

#--------------------------#--------------------------#--------------------------#--------------------------
#--------------------------#--------------------------#--------------------------#--------------------------


if __name__ == '__main__':

# sub_1 용  #--------------------------#--------------------------#--------------------------
    def subscribe_module_1_info_callback(msg) -> None:
        print('hihi i got msg : [{}]'.format(msg))

    NODE_NAME_1_SUB = 'sub_thread_test_1'
    MSG_TYPE_1_SUB = String
    TOPIC_1_SUB = '/sub_thread_test_1/test'
    RATE_HZ_1_SUB = '2.0'
    CALLBACK_1_SUB = subscribe_module_1_info_callback

    _subscribe_module_1_info = {
        'module_name': NODE_NAME_1_SUB,
        'node_info': {
            'node_name': NODE_NAME_1_SUB,
            'msg_type': MSG_TYPE_1_SUB,
            'topic_name': TOPIC_1_SUB,
            'rate_sec': RATE_HZ_1_SUB,
            'callback_func': CALLBACK_1_SUB
        }
    }

# sub_2 용  #--------------------------#--------------------------#--------------------------
    def subscribe_module_2_info_callback(msg) -> None:
        print('hihi i got msg : [{}]'.format(msg))


    NODE_NAME_2_SUB = 'sub_thread_test_2'
    MSG_TYPE_2_SUB = String
    TOPIC_2_SUB = '/sub_thread_test_2/test'
    RATE_HZ_2_SUB = '2.0'
    CALLBACK_2_SUB = subscribe_module_2_info_callback

    _subscribe_module_2_info = {
        'module_name': NODE_NAME_2_SUB,
        'node_info': {
            'node_name': NODE_NAME_2_SUB,
            'msg_type': MSG_TYPE_2_SUB,
            'topic_name': TOPIC_2_SUB,
            'rate_sec': RATE_HZ_2_SUB,
            'callback_func': CALLBACK_2_SUB
        }
    }

    class aa():
        def __init__(self):
            #sub_1 메이킹
            _subscribe_module_1_obj = Ros2SubNodeAgent(_subscribe_module_1_info)
            _subscribe_module_1_obj.set_up_sub()
            self._sub_node_1_obj = _subscribe_module_1_obj.get_node_obj_id()
            # sub_2 메이킹
            _subscribe_module_2_obj = Ros2SubNodeAgent(_subscribe_module_2_info)
            _subscribe_module_2_obj.set_up_sub()
            self._sub_node_2_obj = _subscribe_module_2_obj.get_node_obj_id()
            # _executor 메이킹
            self._executor = rclpy.executors.MultiThreadedExecutor()



        def run(self):
            """
            _executor에 해당 노드 추가 후 쓰레딩
            """
            self._executor.add_node(self._sub_node_1_obj)
            self._executor.add_node(self._sub_node_2_obj)
            _executor_thread = threading.Thread(target=self._executor.spin, daemon=True)
            _executor_thread.start()
            # _executor_thread.join()

    a = aa()
    a.run()

    while rclpy.ok():
        time.sleep(3)
        print('im waiting publisher')

# 다른 터미널에서 이 명령어 쳐서 받는지 확인하면 끝
# ros2 topic pub --once /sub_thread_test_1/test std_msgs/msg/String "data : thread 1 hi!"
# ros2 topic pub --once /sub_thread_test_2/test std_msgs/msg/String "data : thread 2 hi!"

출력값

 

 

댓글