-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Posible bug: spin_some only processes one message per topic even if m…
…ultiple messages are in the queue ros2/rclcpp#2655 Signed-off-by: Tomoya Fujita <[email protected]>
- Loading branch information
1 parent
04d3995
commit 7876b38
Showing
2 changed files
with
43 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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; | ||
} |