[ROS2-Crystal] rclcpp::executors Interrupt guard condition
Hi,
After upgrading to ROS2 crystal clemmys, I am receiving a error message:
Failed to create interrupt guard condition in Executor constructor
The same code was used in ROS bouncy but for some reason I am receiving the above mentioned error on Crystal.
The source of the issue is caused when assigning the executor rclcpp::executors::SingleThreadedExecutor executor;
.
I am currently trying to pass arguments on assignment to avoid this error message. Was there any changes to how the executors should be called on crystal?
Update:
I tried to reproduce the error message using a simple example using a pure ROS package. I received a different error message this time but, I believe it something to do with the original issue I am facing.
#include <iostream>
#include "rclcpp/executor.hpp"
#include "std_msgs/msg/string.hpp"
#include "rclcpp/rclcpp.hpp"
std::shared_ptr<rclcpp::Node> master_node;
void static topic_callback(std_msgs::msg::String::SharedPtr msg)
{
std::cout <<" Subscriber Received [" << msg->data << "]" << std::endl;
}
int main(){
rclcpp::init(0, nullptr);
rclcpp::executors::MultiThreadedExecutor executor;
master_node = rclcpp::Node::make_shared("MasterNode");
auto subscription_ = master_node->create_subscription<std_msgs::msg::String>("TopicName",topic_callback);
executor.add_node(master_node);
executor.spin_node_some(master_node);
}
Just to give a little background on what I am trying to do. Script A is the main code. I will initialize ROS and create a node in script B.
The std::shared_ptr<rclcpp::Node> master_node;
is being saved in a Header file of script B which will be used as a global variable.
Other scrips will use this pointer to create their publishers and subscribers.
For example script C will create a publisher publisher_ = master_node->create_publisher<std_msgs::msg::String>("topic");
and script D will subscribe to said publisher or other publishers subscription_ = master_node->create_subscription<std_msgs::msg::String>("TopicName",topic_callback);
.
The reason I want to use (Single/Multi)ThreadingExecutor is due to main code's thread being used in other matters.
Update2:
I believe the following is a better representation of my current code.
using rclcpp::executors::MultiThreadedExecutor;
std::shared_ptr<rclcpp::Node> master_node;
void topic_callback(std_msgs::msg::String::SharedPtr msg)
{
std::cout <<" Subscriber Received [" << msg->data << "]" << std::endl;
}
int main(){
rclcpp::init(0, nullptr);
MultiThreadedExecutor executor;
master_node = rclcpp::Node::make_shared("MasterNode");
auto subscription_ = master_node->create_subscription<std_msgs::msg::String>("TopicName",topic_callback);
executor.add_node(master_node);
std::thread executor_thread(std::bind(&MultiThreadedExecutor::spin, &executor));
executor_thread.detach();
while(true){
std::cout << "hey" << std::endl;
usleep(3000000);
}
}
To be clear, does the snippet above run and then crash?
The update1 code will crash. The update2 code ran without issue. Because I did not see the same error message when using the Update2's code, I began to suspect that some other issue was occurring. It seems that the Interrupt guard condition also occurs if
init
is not called.