From 7876b384decae086e297f80534bb9240e1fe4007 Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Fri, 24 Jan 2025 13:33:20 -0800 Subject: [PATCH] Posible bug: spin_some only processes one message per topic even if multiple messages are in the queue https://github.com/ros2/rclcpp/issues/2655 Signed-off-by: Tomoya Fujita --- prover_rclcpp/CMakeLists.txt | 1 + prover_rclcpp/src/rclcpp_2655.cpp | 42 +++++++++++++++++++++++++++++++ 2 files changed, 43 insertions(+) create mode 100644 prover_rclcpp/src/rclcpp_2655.cpp diff --git a/prover_rclcpp/CMakeLists.txt b/prover_rclcpp/CMakeLists.txt index b66abfa..74d8aaf 100644 --- a/prover_rclcpp/CMakeLists.txt +++ b/prover_rclcpp/CMakeLists.txt @@ -159,6 +159,7 @@ custom_executable(rclcpp_2497) custom_executable(rclcpp_2507) custom_executable(rclcpp_2645) #custom_executable(rclcpp_2654) +custom_executable(rclcpp_2655) custom_executable(rclcpp_2664) custom_executable(rosbag2_1586) diff --git a/prover_rclcpp/src/rclcpp_2655.cpp b/prover_rclcpp/src/rclcpp_2655.cpp new file mode 100644 index 0000000..42310cd --- /dev/null +++ b/prover_rclcpp/src/rclcpp_2655.cpp @@ -0,0 +1,42 @@ +#include +#include +#include + +int main(int argc, char *argv[]) { + rclcpp::init(argc, argv); + + rclcpp::Node::SharedPtr pub_node = std::make_shared("publisher"); + auto pub = pub_node->create_publisher("topic", 100); + int count = 0; + auto timer_pub = pub_node->create_wall_timer(std::chrono::milliseconds(100), [&]() -> void { + std_msgs::msg::String msg; + msg.data = std::to_string(count); + count++; + pub->publish(msg); + std::cout << "Published: " << msg.data << std::endl; + }); + std::thread pub_node_thread([&]() { + rclcpp::spin(pub_node); + }); + + rclcpp::Node::SharedPtr sub_node = std::make_shared("subscriber"); + auto sub1 = + sub_node->create_subscription("topic", 100, [](std_msgs::msg::String::ConstSharedPtr msg) { + std::cout << "Received(sub1): " << msg->data << std::endl; + }); + auto sub2 = + sub_node->create_subscription("topic", 100, [](std_msgs::msg::String::ConstSharedPtr msg) { + std::cout << "Received(sub2): " << msg->data << std::endl; + }); + + while (rclcpp::ok()) { + std::cout << "Running spin_some" << std::endl; + rclcpp::spin_some(sub_node); + std::this_thread::sleep_for(std::chrono::seconds(1)); + } + + pub_node_thread.join(); + rclcpp::shutdown(); + + return 0; +}