Search

[ROS2] Executor와 Callback groups (SingleThreadedExecutor, MultiThreadedExecutor)

Last update:

rclpy.Executor

기본적으로 rclpy는 세 가지 Executor를 제공한다.
SingleThreadedExecutor (default)
StaticSingleThreadedExecutor
MultiThreadedExecutor
각 executor는 아래와 같은 특징을 갖는다.
SingleThreadedExecutor는 콜백 함수를 싱글 쓰레드에서 실행한다. 따라서 하나의 콜백 함수가 종료되어야 다른 콜백 함수가 실행될 수 있다.
StaticSingleThreadedExecutor는 런타임에 노드의 엔터티(subscription, timer, service server, action server)를 스캐닝하지 않도록 최적화한 executor로, 초기화 시에 모든 엔터티를 생성하는 노드에 적용할 수 있다. 여기서는 SingleThreadedExecutor와 따로 구분하지는 않겠다.
MultiThreadedExecutor는 여러 콜백 함수를 동시에 실행할 수 있다. 따라서 SingleThreadedExecutor와는 다르게 callback group 옵션을 적용할 수 있다.
이 포스트에서는 rclpy의 인터페이스를 기준으로 설명을 한다. C++에서의 사용법은 공식 문서를 참고하자.

MultiThreadedExecutor의 callback group option

rclpy에서는 MultiThreadedExecutor와 사용할 수 있는 두 가지 callback group 옵션을 제공한다.
MutuallyExclusiveCallbackGroup
ReentrantCallbackGroup
각 callback group에 대한 설명은 아래와 같다.
MutuallyExclusiveCallbackGroup은 동시에 최대 하나의 콜백 함수만 실행할 수 있도록 하는 옵션이다. 따라서 여러 콜백 함수에서 non-thread-safe 리소스에 동시에 접근할 수 없도록 한다. 즉, 리소스에 대한 상호 배제 조건이 필요한 콜백은 이 그룹에 넣으면 된다.
ReentrantCallbackGroup은 그룹 내 콜백들을 제한 없이 동시 실행할 수 있도록 하는데, 심지어 같은 콜백의 다른 인스턴스를 동시에 실행할 수도 있다(예를 들어 타이머 콜백의 실행 시간이 타이머 간격보다 긴 경우).
콜백 함수에 대해 아래 두 가지 사항을 염두해두고 있어야 한다.
ros2의 거의 모든 것은 콜백함수다. Executor에 의해 실행되는 모든 함수는 정의상 콜백함수다.
가끔 이 콜백함수는 rclpy에서 제공하는 유저나 개발자 API에서는 명백하게 그 존재가 보이지 않을 때가 있는데, 특히 서비스나 액션에 대한 동기 호출이 그렇다. 예를 들어 동기 호출인 Client.call(request) API는, call() 함수가 실행되는 동안, 내부적으로는 Futuredone 콜백함수를 추가하지만 유저에게 명시적으로 보여지지는 않는다.
따라서 콜백 그룹의 실행을 제어하기 위해 아래 가이드라인을 따르면 좋다.
중요한 non-thread-safe 리소스에 접근하는 콜백 함수들은 MutuallyExclusiveCallbackGroup에 등록하거나 수동으로 lock 절차를 넣는다.
같은 콜백 함수의 여러 인스턴스가 서로 겹칠(overlay) 수 있어야 하는 콜백 함수는 ReentrantCallbackGroup에 등록한다.
병렬로 실행될 수 있어야 하는 콜백 함수들은 ReentrantCallbackGroup이나 별도의 MutuallyExclusiveCallbackGroup에 등록한다. MutuallyExclusiveCallbackGroup에 등록하는 경우는, 같은 종류의 콜백 함수끼리는 겹치지 않도록

데드락 피하기

보통은 콜백 함수 내에서 서비스나 액션에 대한 동기 호출을 하는 경우 데드락이 일어나기 때문에, 콜배인식이 있는데, 완전히 맞는 말은 아니다. 동기 호출을 사용하면 SingleThreadedExecutors에서도 데드락에 안전하도록 코딩할 수 있지만, 동기 호출 또한 콜백 그룹만 잘 지정되어 있다면 역시 데드락에 안전하도록 사용할 수 있다. 동기 호출은 코드를 깔끔하고 이해하기 쉽도록 만들기 때문에, 데드락의 위험만 제거할 수 있다면 동기호출도 사용할 가치가 있다.
우선 모든 노드의 default 콜백 그룹은 MutuallyExclusiveCallbackGroup이라는 점을 알아야 한다. 유저가 timer, subscription, client 등의 엔터티를 생성할 때 특별히 콜백 그룹을 지정하지 않으면 이 엔터티가 생성하는 콜백은 노드의 default callback group에 들어간다. 게다가 노드의 모든 엔티티가 하나의 MutuallyExclusiveCallbackGroup을 사용하는 경우, 그 노드는 MultiThreadedExecutor에 의해 실행됨에도 본질적으로 SingleThreadedExecutor에 의해 실행되는 것처럼 행동한다. 따라서 MultiThreadedExecutor를 사용하기로 했다면 그것이 의미가 있도록 몇몇 콜백 그룹을 지정할 필요가 있다.
따라서 데드락을 피하기 위한 가이드라인은 아래와 같다.
비동기 호출 사용하기
콜백 함수 내에서 동기 호출을 사용할 경우에는, 이 콜백 함수와 그것을 사용하는 클라이언트가 아래 둘 중 하나에 속하도록 하기
각각 다른 콜백 그룹(타입 무관)
ReentrantCallbackGroup
만약 두 번째 지침을 어기는 경우 항상 데드락이 일어난다.

예시

from threading import Thread from time import sleep import rclpy from rclpy.executors import SingleThreadedExecutor, MultiThreadedExecutor from rclpy.callback_groups import MutuallyExclusiveCallbackGroup, ReentrantCallbackGroup from rclpy.node import Node from std_srvs.srv import Empty class ServiceNode(Node): def __init__(self): super().__init__('mock_service_node') self.srv = self.create_service(Empty, 'test_service', callback=self.service_callback) self.call_timer = self.create_timer(1, self.timer_cb, callback_group=timer_cb_group) def service_callback(self, request, result): self.get_logger().info('Server received request') return result class ClientNode(Node): def __init__(self, client_cb_group, timer_cb_group): super().__init__('client_node') self.client = self.create_client(Empty, 'test_service', callback_group=client_cb_group) self.call_timer = self.create_timer(1, self.timer_cb, callback_group=timer_cb_group) def timer_cb(self): self.get_logger().info('Client sending request') _ = self.client.call(Empty.Request()) self.get_logger().info('Client received response') def spin_srv(executor): try: executor.spin() except rclpy.executors.ExternalShutdownException: pass def run_test(client_cb_group, timer_cb_group): rclpy.init() service_node = ServiceNode() srv_executor = SingleThreadedExecutor() srv_executor.add_node(service_node) srv_thread = Thread(target=spin_srv, args=(srv_executor, ), daemon=True) srv_thread.start() client_node = ClientNode(client_cb_group=client_cb_group, timer_cb_group=timer_cb_group) client_executor = MultiThreadedExecutor() client_executor.add_node(client_node) try: print("") client_node.get_logger().info('Beginning demo, end with CTRL-C') client_executor.spin() except KeyboardInterrupt: client_node.get_logger().info('KeyboardInterrupt, shutting down.\n') client_node.destroy_node() service_node.destroy_node() rclpy.shutdown() try: srv_thread.join() except KeyboardInterrupt: pass if __name__ == '__main__': run_test(client_cb_group=None, timer_cb_group=None) # deadlock mutexGroup1 = MutuallyExclusiveCallbackGroup() mutexGroup2 = MutuallyExclusiveCallbackGroup() run_test(client_cb_group=mutexGroup1, timer_cb_group=None) # ok run_test(client_cb_group=None, timer_cb_group=mutexGroup2) # ok run_test(client_cb_group=mutexGroup1, timer_cb_group=mutexGroup2) # ok mutexGroup3 = MutuallyExclusiveCallbackGroup() run_test(client_cb_group=mutexGroup3, timer_cb_group=mutexGroup3) # deadlock reentrant_group = ReentrantCallbackGroup() run_test(client_cb_group=reentrant_group, timer_cb_group=reentrant_group) # ok
Python
복사
위의 경우에서, ClientNode를 보면 timer 내에서 client를 통해 service call을 하는 것을 볼 수 있다.
class ClientNode(Node): def __init__(self, client_cb_group, timer_cb_group): super().__init__('client_node') self.client = self.create_client(Empty, 'test_service', callback_group=client_cb_group) self.call_timer = self.create_timer(1, self.timer_cb, callback_group=timer_cb_group) def timer_cb(self): self.get_logger().info('Client sending request') _ = self.client.call(Empty.Request()) self.get_logger().info('Client received response')
Python
복사
이때 client의 그룹과 timer의 그룹이 같은 MutuallyExclusiveCallbackGroup 내에 속할 경우 아래와 같은 원리에 의해 deadlock이 걸린다.
1.
timer의 callback 함수가 호출됨
2.
timer의 callback 함수가 호출하는 _call_srv(...) 함수에서 self.client.call(...) 함수 호출
3.
self.client.call(...) 함수 내부에서 done callback 함수가 호출되지 못함
4.
self.client.call(...) 함수는 반환되지 못하고, 결과적으로 timer의 callback 함수도 종료되지 않은 채 deadlock
즉, 아래와 같은 케이스는 deadlock이 걸린다.
default MutuallyExclusiveCallbackGroup에 속하는 경우
run_test(client_cb_group=None, timer_cb_group=None) # deadlock
Python
복사
같은 MutuallyExclusiveCallbackGroup에 속하는 경우
mutexGroup3 = MutuallyExclusiveCallbackGroup() run_test(client_cb_group=mutexGroup3, timer_cb_group=mutexGroup3) # deadlock
Python
복사
나머지 케이스는 deadlock이 걸리지 않는다.
다른 MutuallyExclusiveCallbackGroup에 속하는 경우
mutexGroup1 = MutuallyExclusiveCallbackGroup() mutexGroup2 = MutuallyExclusiveCallbackGroup() run_test(client_cb_group=mutexGroup1, timer_cb_group=None) # ok run_test(client_cb_group=None, timer_cb_group=mutexGroup2) # ok run_test(client_cb_group=mutexGroup1, timer_cb_group=mutexGroup2) # ok reentrant_group = ReentrantCallbackGroup() run_test(client_cb_group=reentrant_group, timer_cb_group=reentrant_group) # ok
Python
복사
같거나 다른 ReentrantCallbackGroup에 속하는 경우
reentrant_group = ReentrantCallbackGroup() run_test(client_cb_group=reentrant_group, timer_cb_group=reentrant_group) # ok
Python
복사

References

관련 문서