ROS timer not working after including CallbackGroups
Hi everyone, I have a question regarding the CallbackGroups of rclcpp in ROS2. I'm trying to have an update cycle run by a rclcpp::TimerBase run on a specified update rate and at the same time the node should listen to an incoming message on a subscription. The way to do it, as I have understood it, is to use a MultiThreadExceutor with CallbackGroups. I therfore created a Reentrant Type CallbackGroup to which I added both the timer and the subscription. As soon as I add the timer to the CallbackGroup the timer stops working, however. Maybe I forgot something? Does the CallbackGroups or Node need to be in a specified Context maybe? Or did I misunderstand the concept of CallbackGroups altogether? Would be happy about any help from you!
Code:
Header file: controller_node_test/controller_node_test.h:
#ifndef CONTROLLER_NODE_H
#define CONTROLLER_NODE_H
#include "rclcpp/rclcpp.hpp"
#include "controller_node_test/multi_threaded_executor.hpp"
#include "chrono"
#include <ctime>
using std::placeholders::_1;
namespace controller_node
{
class ControllerNode : public rclcpp::Node {
public:
ControllerNode();
~ControllerNode();
private:
rclcpp::TimerBase::SharedPtr update_timer_;
void update();
};
} // namespace controller_node
Source: controller_node_test.cpp:
#include "controller_node_test/controller_node_test.h"
namespace controller_node
{
ControllerNode::ControllerNode() : rclcpp::Node("controller_node"){
rclcpp::callback_group::CallbackGroup::SharedPtr update_group = this->create_callback_group(rclcpp::callback_group::CallbackGroupType::Reentrant);
update_timer_ = this->create_wall_timer(
std::chrono::milliseconds(100),
std::bind(&ControllerNode::update, this),
update_group);
}
ControllerNode::~ControllerNode(){
}
void ControllerNode::update(){
std::cout << "Timer: " << std::this_thread::get_id() << std::endl;
}
} // namespace controller_node
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::executors::MultiThreadedExecutor exec;
auto controller_node = std::make_shared<controller_node::ControllerNode>();
exec.add_node(controller_node);
exec.spin();
rclcpp::shutdown();
return 0;
}
The problem is, that
std::cout << "Timer: " << std::this_thread::get_id() << std::endl;
never gets called, so the timer is not working, at all.
I deleted all not necessary parts of the Code to make it more clear for you, so if it doesn't compile let me know. Would really appreciate any help!
What I tried so far: SingleThreadExecutor shows the same problem, Removing the CallbackGroup shows the expected behavior, timer is running and update() is called. Tried to isolate the problem and found out, that it is during the run(...) method of the MTE, in the get_next_executable(:::) of the parent class (rclcpp::executor::Executor) in the wait_for_work(...) function of the Executor in line 447-448:
rcl_ret_t status = rcl_wait(&wait_set_, std::chrono::duration_cast<std::chrono::nanoseconds>(timeout).count());
and if I give out
memory_strategy_->number_of_ready_timers()
in the MultiThreadedExecutor it shows me 1, so the timer seems to be registered, right?
if that helps at all. I just don't understand what exactly is happening there and now I need your help... Thanks!
Okay, apparently multiple CallbackGroups result in an infinite "wait_for_work". Related Github: #814 Switching to different Nodes in MultiThreadedExecutor now