ROS2에서는 callback group이라는 개념이 있다. callback group을 모르고 개발하다 보면 특수한 상황에서 deadlock이 발생할 수도 있다.
Callback group 이란?
기본적으로 ROS는 수 많은 Callback function들을 사용하게 된다. (topic subscriber, service server, action server 등) 이런 Callback function들을 관리하기 위해 사용되는 것이 Callback group이다. Callback group은 2가지 유형을 제공한다.
- Mutually Exclusive Callback Group
- Reentrant Callback Group
두가지의 차이점은 뭘까? 첫 번째로 Mutually Exclusive Callback Group 은 같은 group 내에 있는 Callback function들을 SingleThread처럼 순차적으로 처리하게 된다. 그에 반해 Reentrant Callback Group은 동시에 같은 group 내에 Callback function을 처리한다.
Callback group 등록하는 방법
my_callback_group = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
rclcpp::SubscriptionOptions options;
options.callback_group = my_callback_group;
my_subscription = create_subscription<Int32>("/topic", rclcpp::SensorDataQoS(),
callback, options);
위 코드처럼 Callback group을 등록할 수 있다. 하지만 ROS2를 접한 지 오래되지 않았다면 Callback group을 등록해보지 않았을 수도 있다. 등록이 안되어 있다면 Node의 기본 Callback group인 Mutually Exclusive Callback Group으로 설정된다. 기본 설정 값은 NodeBaseInterface::get_default_callback_group()로 확인 가능하다.
실행 제어 가이드라인
ROS2 문서에서는 Mutually Exclusive와 Reentrant 방식에 대한 가이드라인을 제공해 주고 있다.
- 자체적으로 병렬로 실행해야 할 경우 Reentrant로 등록한다. 예) 여러 번의 호출을 지원하는 Service, Action
- 자체적으로 병렬로 실행하면 안되는 경우 Mutually Exclusive로 등록한다. 예) 제어를 담당하는 Timer
- 병렬로 실행해야 하는 경우 Reentrant, 혹은 서로 다른 Mutually Exclusive에 등록한다.
Callback group으로 인한 deadlock
ROS로 개발하다 보면 Callback group으로 인해 Node가 deadlock 상태에 빠질 수 있다. 아래와 같은 상황을 생각해 보자.
Subscriber callback function 안에서 Service 호출
#include <chrono>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_srvs/srv/empty.hpp"
using namespace std::chrono_literals;
namespace cb_group_demo
{
class DemoNode : public rclcpp::Node
{
public:
DemoNode() : Node("client_node")
{
client_cb_group_ = nullptr;
timer_cb_group_ = nullptr;
client_ptr_ = this->create_client<std_srvs::srv::Empty>("test_service", rmw_qos_profile_services_default,
client_cb_group_);
timer_ptr_ = this->create_wall_timer(1s, std::bind(&DemoNode::timer_callback, this),
timer_cb_group_);
}
private:
rclcpp::CallbackGroup::SharedPtr client_cb_group_;
rclcpp::CallbackGroup::SharedPtr timer_cb_group_;
rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_ptr_;
rclcpp::TimerBase::SharedPtr timer_ptr_;
void timer_callback()
{
RCLCPP_INFO(this->get_logger(), "Sending request");
auto request = std::make_shared<std_srvs::srv::Empty::Request>();
auto result_future = client_ptr_->async_send_request(request);
std::future_status status = result_future.wait_for(10s); // timeout to guarantee a graceful finish
if (status == std::future_status::ready) {
RCLCPP_INFO(this->get_logger(), "Received response");
}
}
}; // class DemoNode
} // namespace cb_group_demo
int main(int argc, char* argv[])
{
rclcpp::init(argc, argv);
auto client_node = std::make_shared<cb_group_demo::DemoNode>();
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(client_node);
RCLCPP_INFO(client_node->get_logger(), "Starting client node, shut down with CTRL-C");
executor.spin();
RCLCPP_INFO(client_node->get_logger(), "Keyboard interrupt, shutting down.\n");
rclcpp::shutdown();
return 0;
}
Subscriber callback function 안에서 Service를 호출한다고 생각해 보자. 두 callback 함수는 동일한 callback group에 포함되어 있으며 Mutually Exclusive 유형이다. 우리가 아마 원하는 결과는 Topic에 값이 전송될 때마다 Service를 호출하는 것이다. 하지만 위 프로그램은 Deadlock에 빠지게 된다. 실행 결과를 확인해 보자.
[INFO] [1653034371.758739131] [client_node]: Starting client node, shut down with CTRL-C
[INFO] [1653034372.755865649] [client_node]: Sending request
^C[INFO] [1653034398.161674869] [client_node]: Keyboard interrupt, shutting down.
Deadlock에 빠지게 되는 이유는 둘은 동일한 Mutually Exclusive 유형 Callback group 안에 등록되어 있다. 그러므로 병렬적으로 수행할 수 없어 생기는 문제이다. flow를 확인해 보자.
- Topic Subscriber callback 호출
- Service Client callback 호출
- Topic Subscriber callback 끝날 때까지 대기 (Deadlock)
Topic Subscriber가 끝난 뒤에 Service가 끝나게 되는데 Service는 Topic Subscriber가 끝날때 까지 대기하게 된다. 즉 Deadlock이 발생하게 된다.
해결방법
Reentrant 유형의 Callback group을 사용하거나 서로 다른 Mutually exclusive 유형의 Callback group을 사용하여 해결할 수 있다.
client_cb_group_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
timer_cb_group_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
위 코드처럼 서로 다른 Callback group으로 변경한 뒤 다시 실행해보면 우리가 원하는 결과를 얻을 수 있다.
[INFO] [1653067523.431731177] [client_node]: Starting client node, shut down with CTRL-C
[INFO] [1653067524.431912821] [client_node]: Sending request
[INFO] [1653067524.433230445] [client_node]: Received response
[INFO] [1653067525.431869330] [client_node]: Sending request
[INFO] [1653067525.432912803] [client_node]: Received response
[INFO] [1653067526.431844726] [client_node]: Sending request
[INFO] [1653067526.432893954] [client_node]: Received response
[INFO] [1653067527.431828287] [client_node]: Sending request
[INFO] [1653067527.432848369] [client_node]: Received response
^C[INFO] [1653067528.400052749] [client_node]: Keyboard interrupt, shutting down.
참고
'ROS' 카테고리의 다른 글
[Nav2] AMCL(Adaptive Monte Carlo Localization) package 분석 (0) | 2024.01.09 |
---|---|
[ROS2] Life cycle node 개념 및 Nav2 예시 살펴보기 (0) | 2024.01.04 |
[ROS2] DDS와 RMW 개념 및 QoS 호환성 확인 (0) | 2023.12.05 |
ROS1 Noetic Arduino와 Serial 통신하기 (0) | 2022.07.15 |