一、问题描述及解决
在 ROS 2 中,默认情况下,节点的回调函数是在单线程执行器(Single-Threaded Executor)中执行的。这意味着所有回调函数都会在一个线程中顺序执行,不会并行运行。
最近有个项目需要需要多个回调函数同时运行,但是有些回调函数中有while循环,在实际使用上会影响其他回调函数的运行。但作为c++苦手,是在不想去嗑c++多线程使用方式,因此突然想起ROS2中似乎有多线程执行器(Multi-Threaded Executor)和回调组(Callback Groups)的概念,但在实际使用中遇到了不少问题,特以此贴总结回顾。
首先,第一次写出的代码如下
#include <chrono>
#include <memory>
#include <rclcpp/rclcpp.hpp>
#include "std_msgs/msg/int32.hpp"
using namespace std::chrono_literals;
class MultiThreadedPublisher : public rclcpp::Node
{
public:
MultiThreadedPublisher() : Node("multi_threaded_publisher")
{
// // 声明回调组
rclcpp::CallbackGroup::SharedPtr callback_group;
rclcpp::CallbackGroup::SharedPtr callback_group_2;
// // 实例化回调组
callback_group = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
callback_group_2 = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
// callback_group = nullptr;
timer1_ = this->create_wall_timer(5000ms, std::bind(&MultiThreadedPublisher::publish_message1, this), callback_group);
timer2_ = this->create_wall_timer(1000ms, std::bind(&MultiThreadedPublisher::publish_message2, this), callback_group_2);
}
private:
void publish_message1()
{
RCLCPP_INFO(this->get_logger(), "Publishing on topic1: '%d'", 1);
}
void publish_message2()
{
RCLCPP_INFO(this->get_logger(), "Publishing on topic2: '%d'", 2);
}
rclcpp::TimerBase::SharedPtr timer1_;
rclcpp::TimerBase::SharedPtr timer2_;
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<MultiThreadedPublisher>();
// 使用多线程执行器
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(node);
executor.spin();
rclcpp::shutdown();
return 0;
}
感兴趣的可以试一试,会发现根本无法运行,但是乍看之下似乎并没有问题,因此我也寻找了好久的问题原因,之后在鱼香ROS社区中提问时,有幸得到了小鱼大佬的点拨:
问题原因
callback_group 和 callback_group_2 被定义在构造函数内部,它们将作为局部变量存在,当构造函数执行完毕后,这些局部变量会被销毁。这会导致回调组失效,从而无法正确地执行回调函数。
解决方案
确保 callback_group 和 callback_group_2 被定义为类的成员变量,这样它们的生命周期将与类实例相同,不会在构造函数执行完毕后被销毁。
遂进行修改:
#include <chrono>
#include <memory>
#include <rclcpp/rclcpp.hpp>
#include "std_msgs/msg/int32.hpp"
#include <thread>
using namespace std::chrono_literals;
class MultiThreadedPublisher : public rclcpp::Node
{
public:
MultiThreadedPublisher() : Node("multi_threaded_publisher")
{
// // 实例化回调组
callback_group = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
callback_group_2 = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
// callback_group = nullptr;
timer1_ = this->create_wall_timer(std::chrono::milliseconds(5000), std::bind(&MultiThreadedPublisher::publish_message1, this), callback_group);
timer2_ = this->create_wall_timer(std::chrono::milliseconds(1000), std::bind(&MultiThreadedPublisher::publish_message2, this), callback_group_2);
}
private:
void publish_message1()
{
RCLCPP_INFO(this->get_logger(), "Publishing on topic1: '%d'", 1);
}
void publish_message2()
{
RCLCPP_INFO(this->get_logger(), "Publishing on topic2: '%d'", 2);
}
rclcpp::TimerBase::SharedPtr timer1_;
rclcpp::TimerBase::SharedPtr timer2_;
// // 声明回调组
rclcpp::CallbackGroup::SharedPtr callback_group;
rclcpp::CallbackGroup::SharedPtr callback_group_2;
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
rclcpp::executors::MultiThreadedExecutor executor(rclcpp::ExecutorOptions(), 20, true);
auto node = std::make_shared<MultiThreadedPublisher>();
executor.add_node(node);
executor.spin();
rclcpp::shutdown();
return 0;
}
这次可以完美运行啦!
但是之后又遇到了另外一个问题,但回调函数中有while循环时,使用ctrl+c是无法立刻结束程序的,之后在ros多线程C++多线程ROS程序CTRL C无法退出问题解决中找到了一丝灵感,之后根据一个大佬的开源代码,对程序进行了一下修改
#include <chrono>
#include <memory>
#include <rclcpp/rclcpp.hpp>
#include "std_msgs/msg/int32.hpp"
#include <thread>
bool ctrl_flag = false;
static void my_handler(int sig) // can be called asynchronously
{
ctrl_flag = true; // set flag
}
using namespace std::chrono_literals;
class MultiThreadedPublisher : public rclcpp::Node
{
public:
MultiThreadedPublisher() : Node("multi_threaded_publisher")
{
// // 实例化回调组
callback_group = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
callback_group_2 = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
// callback_group = nullptr;
timer1_ = this->create_wall_timer(std::chrono::milliseconds(5000), std::bind(&MultiThreadedPublisher::publish_message1, this), callback_group);
timer2_ = this->create_wall_timer(std::chrono::milliseconds(1000), std::bind(&MultiThreadedPublisher::publish_message2, this), callback_group_2);
}
private:
void publish_message1()
{
while (1)
{
if (ctrl_flag == true)
{
rclcpp::shutdown();
exit(0);
}
usleep(10000);
RCLCPP_INFO(this->get_logger(), "Publishing on topic1: '%d'", 1);
}
}
void publish_message2()
{
RCLCPP_INFO(this->get_logger(), "Publishing on topic2: '%d'", 2);
}
rclcpp::TimerBase::SharedPtr timer1_;
rclcpp::TimerBase::SharedPtr timer2_;
// 声明回调组 必须放在这里!!
rclcpp::CallbackGroup::SharedPtr callback_group;
rclcpp::CallbackGroup::SharedPtr callback_group_2;
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
signal(SIGINT, my_handler);
rclcpp::executors::MultiThreadedExecutor executor(rclcpp::ExecutorOptions(), 20, true);
auto node = std::make_shared<MultiThreadedPublisher>();
executor.add_node(node);
executor.spin();
rclcpp::shutdown();
return 0;
return EXIT_SUCCESS;
}
这样即使有while循环也可以结束程序
二、总结
2-1 什么地方可以使用回调组
在 ROS 2 中,回调组(Callback Groups)主要用于管理节点中的各种回调,以控制它们的执行方式和并发行为。以下是一些可以使用回调组的地方:
首先需要创建订阅选项,并设置回调组
rclcpp::SubscriptionOptions options;
options_1.callback_group = callback_group_1;
- 订阅者(Subscribers)
当你创建一个订阅者时,可以指定一个回调组。这样可以控制订阅者回调的执行方式,例如是否与其他回调并行执行。
auto subscription = this->create_subscription<std_msgs::msg::String>(
"topic", 10, std::bind(&MyNode::topic_callback, this, std::placeholders::_1), options);
- 计时器(Timers)
计时器的回调也可以通过回调组来管理。这对于需要定期执行的任务非常有用,你可以通过回调组来控制这些任务的并发执行。
auto timer = this->create_wall_timer(
std::chrono::milliseconds(1000), std::bind(&MyNode::timer_callback, this), options);
- 服务服务器(Service Servers)
服务服务器的回调可以使用回调组来管理。这对于需要在特定条件下并行处理多个服务请求的场景非常有用。
auto service = this->create_service<example_interfaces::srv::AddTwoInts>(
"add_two_ints", std::bind(&MyNode::service_callback, this, std::placeholders::_1, std::placeholders::_2), options);
- 动态参数(Dynamic Parameters)
如果你使用动态参数,其回调也可以通过回调组来管理。这对于需要在参数变化时执行特定操作的场景很有用。
auto param_callback = this->add_on_set_parameters_callback(
std::bind(&MyNode::param_callback, this, std::placeholders::_1), options);
- 客户端(Clients)
客户端的回调也可以使用回调组来管理,特别是在使用异步客户端时,你可以通过回调组来控制这些回调的执行方式.
auto client = this->create_client<example_interfaces::srv::AddTwoInts>(
"add_two_ints", options);
2-2 回调组
互斥回调组(Mutually Exclusive Callback Group):
这种回调组会阻止其内部的回调函数并行执行。换句话说,组内的回调函数会像在单线程执行器中一样顺序执行
。适用于需要确保回调函数不会同时访问共享资源的情况
可重入回调组(Reentrant Callback Group):
这种回调组允许执行器以任何方式安排和执行组内的回调函数,没有限制。
这意味着不仅不同的回调函数可以并行执行,同一回调函数的不同实例也可以并发执行。适用于需要并行处理多个请求或消息的场景。
2-3 signal(SIGINT, my_handler);
在 C 或 C++ 程序中,signal(SIGINT, my_handler); 这行代码用于设置一个信号处理函数,以便在程序接收到 SIGINT 信号时调用 my_handler 函数。SIGINT 是一个中断信号,通常由用户按下 Ctrl+C 产生,用于请求程序终止.
解释各部分的作用:
signal 函数:
该函数用于设置信号处理函数。
原型:void (*signal(int signum, void (*handler)(int)))(int);
参数:
signum:要处理的信号类型。在本例中是 SIGINT。
handler:信号处理函数的指针。在本例中是 my_handler。
返回值:返回之前为该信号设置的处理函数指针,如果出错则返回 SIG_ERR。
SIGINT:
是一个信号类型,表示中断信号。当用户按下 Ctrl+C 时,操作系统会向当前进程发送 SIGINT 信号。
以上总结均来自KIMI,如有错误,烦请勘误