You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
#include<chrono>
#include<future>
#include<thread>
#include<rclcpp/rclcpp.hpp>
#include<std_msgs/msg/string.hpp>intmain(int argc, char** argv) {
rclcpp::init(argc, argv);
// Publish a string message on a latched ros topicconst std::string topic_name = "/pub_topic";
std_msgs::msg::String rosMsg;
rosMsg.data = "hello world";
auto sub_node = rclcpp::Node::make_shared("sub");
auto pub_node = rclcpp::Node::make_shared("pub");
rclcpp::QoS qos = rclcpp::QoS{rclcpp::KeepLast(1lu)};
qos.transient_local();
auto pub = pub_node->create_publisher<std_msgs::msg::String>(topic_name, qos);
pub->publish(rosMsg);
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(pub_node);
executor.add_node(sub_node);
auto callbackGroupCreatedBeforeSpin =
sub_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
std::thread spinnerThread([&executor]() {
executor.spin();
});
std::this_thread::sleep_for(std::chrono::milliseconds(100));
auto callbackGroupCreatedAfterSpin =
sub_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
// Subscribe to the topic and verify that we have received a message.
rclcpp::SubscriptionOptions subscriptionOptions;
subscriptionOptions.callback_group = callbackGroupCreatedAfterSpin; // This doesn't work// subscriptionOptions.callback_group = callbackGroupCreatedBeforeSpin; // This works
std::promise<void> msgReceivedPromise;
auto msgFuture = msgReceivedPromise.get_future();
auto sub = sub_node->create_generic_subscription(
topic_name, "std_msgs/msg/String", qos,
[&msgReceivedPromise](std::shared_ptr<rclcpp::SerializedMessage>) {
msgReceivedPromise.set_value();
},
subscriptionOptions);
int ret = EXIT_SUCCESS;
if (std::future_status::ready == msgFuture.wait_for(std::chrono::milliseconds(500))) {
RCLCPP_INFO(sub_node->get_logger(), "Message received");
} else {
RCLCPP_ERROR(sub_node->get_logger(), "Message NOT received");
ret = EXIT_FAILURE;
}
executor.cancel();
spinnerThread.join();
rclcpp::shutdown();
return ret;
}
Expected behavior
In the above program, I expect that the created subscription receives the message, even when the callback group was created after the executor started spinning
Actual behavior
No message is received. It only works with a callback group that is created before the executor starts spinning. It seems like the
Additional information
Above program works as expected under humble
It seems that the executor is not notified when creating a callback group. I can manually add it with e.g.
**Public-Facing Changes**
- Fix subscriptions not working on rolling
**Description**
- Callback groups that are created after the executor is already
spinning do not work correctly, see
ros2/rclcpp#2067
- Instead of dynamically creating callback groups for each advertised
channel, we now use a single reentrant callback group for all channels
- Consequence is, that message callbacks of the same topic (e.g. when
having multiple clients) can now be called in parallel. However, this is
fine since the `server::sendMessage` is thread safe (also, callbacks of
different topics were already called in parallel)
Fixes#94Fixes#120
Bug report
Required Info:
Ubuntu 22.04.1 LTS
ros:rolling-ros-base
(sha256:598b008cacac6743996ece646095ea7bc541df9e59f596bf6e31d61721a17e71)rmw_fastrtps_cpp
rclcpp
Steps to reproduce issue
Expected behavior
In the above program, I expect that the created subscription receives the message, even when the callback group was created after the executor started spinning
Actual behavior
No message is received. It only works with a callback group that is created before the executor starts spinning. It seems like the
Additional information
Above program works as expected under
humble
It seems that the executor is not notified when creating a callback group. I can manually add it with e.g.
executor.add_callback_group(callbackGroupCreatedAfterSpin, sub_node->get_node_base_interface());
but I can't do that inside a class that inherits from
rclcpp::Node
and which has no access to the executorThe text was updated successfully, but these errors were encountered: