Skip to content

Commit

Permalink
Posible bug: spin_some only processes one message per topic even if m…
Browse files Browse the repository at this point in the history
…ultiple messages are in the queue

  ros2/rclcpp#2655

Signed-off-by: Tomoya Fujita <[email protected]>
  • Loading branch information
fujitatomoya committed Jan 24, 2025
1 parent 04d3995 commit 7876b38
Show file tree
Hide file tree
Showing 2 changed files with 43 additions and 0 deletions.
1 change: 1 addition & 0 deletions prover_rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
42 changes: 42 additions & 0 deletions prover_rclcpp/src/rclcpp_2655.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
#include <rclcpp/node.hpp>
#include <rclcpp/executors.hpp>
#include <std_msgs/msg/string.hpp>

int main(int argc, char *argv[]) {
rclcpp::init(argc, argv);

rclcpp::Node::SharedPtr pub_node = std::make_shared<rclcpp::Node>("publisher");
auto pub = pub_node->create_publisher<std_msgs::msg::String>("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<rclcpp::Node>("subscriber");
auto sub1 =
sub_node->create_subscription<std_msgs::msg::String>("topic", 100, [](std_msgs::msg::String::ConstSharedPtr msg) {
std::cout << "Received(sub1): " << msg->data << std::endl;
});
auto sub2 =
sub_node->create_subscription<std_msgs::msg::String>("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;
}

0 comments on commit 7876b38

Please sign in to comment.