Rospy Multi-Threading

Rospy 사용 시, Subscriber 및 Timer 클래스를 이용하여 인스턴스 생성 시, 각각에 해당하는 콜백 함수를 지정하게 되어 있다.

각각의 처리가 별개의 스레드로 되는 지, 하나의 스레드가 순차적으로 처리하는 지 의문이 들어서 해당 내용을 검색해보았다.

이미 다른 Blog를 찾아보니, 아래와 같다고 하여, 테스트를 해보기로 하였다.

Timer --> 각각이 개별 Thread로 처리
Subscriber --> 각 Topic에 개별 Thread로 처리

Timer Callback

테스트 환경

    Windows 11, WSL2 Ubuntu 18.04
    ROS Melodic Version
    Python 2.7

실행 코드

#!/usr/bin/env python
## timer_multi_thread.py

import rospy
from std_msgs.msg import String

import time

class TimerTester(object):
    '''
    Timer Tester for multi threading
    '''
    def __init__(self):
        self._string_pub = rospy.Publisher("new_msg", String, queue_size=1)
        rospy.Timer(rospy.Duration(1.0 / 0.5), self.slow_callback)
        rospy.Timer(rospy.Duration(1.0 / 1), self.fast_callback)
        
    def slow_callback(self, event):
        rospy.loginfo("slow callback called")
        self._string_pub.publish("slow_callback {}".format(rospy.Time.now()))
        time.sleep(3.0)
        rospy.loginfo("slow callback end")

    def fast_callback(self, event):
        rospy.loginfo("fast callback called")
        self._string_pub.publish("fast_callback {}".format(rospy.Time.now()))
        rospy.loginfo("fast callback end")

def run():
    rospy.init_node("timer_multi_test")
    TimerTester()
    rospy.spin()

if __name__ == "__main__":
    run()

코드 실행 결과

Timer Callback Result


결과 분석

결과를 살펴보면 다음과 같은 내용을 확인할 수 있다.

  • Timer는 Callback이 실행되는 중에는 다시 호출되지 않는다.
  • Timer Callback은 각각의 Thread로 따로 실행이 된다.

첫 번째는 slow_callback 함수 부분을 보면, 중간에 3초의 대기 시간이 있음에도 불구하고, 여러 번 호출이 되지는 않는 모습을 볼 수 있다. 이를 통해, Timer는 하나의 Thread로 처리되며, 해당 Thread가 일을 마치기 전에는 다시 동작하지 않음을 알 수 있다.

두 번째는 slow_callback, fast_callback 두 가지를 동시에 보면 알 수 있는데, slow_callback이 중간에 멈춰 있는 상태에서도 fast_callback은 지속적으로 동작하는 것을 확인할 수 있다. 이를 통해, Timer Callback은 각각의 Thread로 실행된다는 사실을 알 수 있다.


Subscriber Callback

실행 코드

#!/usr/bin/env python
## subscriber_multi_test.py

import rospy
from std_msgs.msg import String

import time

class SubscriberTester(object):
    '''
    Subscriber Tester for multi threading
    '''
    def __init__(self):
        rospy.Subscriber("msg_1", String, self.msg_1_callback_1)
        rospy.Subscriber("msg_1", String, self.msg_1_callback_2)
        rospy.Subscriber("msg_2", String, self.msg_2_callback)
        
    def msg_1_callback_1(self, msg):
        rospy.loginfo("msg_1_callback_1 called {}".format(rospy.Time.now()))
        time.sleep(1.0)
        rospy.loginfo("msg_1_callback_1 end")

    def msg_1_callback_2(self, msg):
        rospy.loginfo("msg_1_callback_2 called {}".format(rospy.Time.now()))
        rospy.loginfo("msg_1_callback_2 end")

    def msg_2_callback(self, msg):
        rospy.loginfo("msg_2_callback called {}".format(rospy.Time.now()))
        rospy.loginfo("msg_2_callback end")

def run():
    rospy.init_node("subscriber_multi_test")
    SubscriberTester()
    rospy.spin()

if __name__ == "__main__":
    run()

코드 실행 결과

Subscriber Callback Result

결과 분석

결과를 보면, 다음과 같은 내용을 확인할 수 있다.

  • 동일한 Topic (msg_1)에 대한 Callback은 순차적으로 처리된다 (같은 스레드로 처리)
  • 다른 Topic (msg_2)에 대한 Callback은 따로 처리된다. (다른 스레드로 처리)

msg_1에 대한 callback 함수는 늘 순서가 동일하다.

    1번 Callback 호출됨
    1번 Callback 내부의 대기가 동작
    1번 Callback 대기 종료
    2번 Callback 호출됨
    2번 Callback 종료

출력되는 내용을 보면 위와 같은 내용을 확인할 수 있고, 늘 처리하는 순서가 정해져 있는 듯 하다.

아마 Subscriber를 정의하는 순서대로가 아닐까 예상됩니다.

따라서, 동일한 Topic에 대한 Callback은 동일한 Thread에서 처리하는 것으로 보입니다.

msg_2에 대한 callback은 msg_1과 상관 없이, 따로 동작하는 것을 볼 수 있습니다.

이에 따라, 다른 Topic에 대한 Callback은 다른 Thread에서 처리하는 것으로 볼 수 있습니다.


최종 결과

  • 기존 블로그에서 확인했던 내용이 거의 맞다.
  • Timer는 1개의 파이썬 코드에서 몇 개를 생성하든, 다른 스레드로 처리된다.
  • Timer는 기존에 수행하고 있는 내용이 종료되지 않으면, 시간이 다 되어도 다시 실행되지 않는다.
  • Subscriber는 1개의 파이썬 코드에서 Topic만 다르면, 다른 스레드로 처리된다.
  • Subscriber는 1개의 파이썬 코드에서 Topic이 같으면, 같은 스레드로 처리된다.

1개의 코드에서 Subscriber를 동일한 Topic에 대해 수행할 일이 있나 싶긴 하지만, 알아두어서 나쁠 것은 없을 것으로 보인다.

추후에 기회가 된다면, roscpp에서의 동작은 어떻게 다른지도 확인해보도록 하겠습니다.

comments