From a2e166ae1b0daf8e3b91d9f7a4c4071d5def2fea Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Wed, 22 Jun 2022 16:50:48 -0700 Subject: [PATCH] [Proposal] Adding single message getting API to rclcpp https://github.com/ros2/rclcpp/issues/1953 Signed-off-by: Tomoya Fujita --- prover_rclcpp/CMakeLists.txt | 1 + prover_rclcpp/src/rclcpp_1953.cpp | 69 +++++++++++++++++++++++++++++++ 2 files changed, 70 insertions(+) create mode 100644 prover_rclcpp/src/rclcpp_1953.cpp diff --git a/prover_rclcpp/CMakeLists.txt b/prover_rclcpp/CMakeLists.txt index 04764e5..765a473 100644 --- a/prover_rclcpp/CMakeLists.txt +++ b/prover_rclcpp/CMakeLists.txt @@ -89,6 +89,7 @@ custom_executable(rclcpp_1827) custom_executable(rclcpp_1876) custom_executable(rclcpp_1915) custom_executable(rclcpp_1925) +custom_executable(rclcpp_1953) custom_executable(rclpy_881) custom_executable(rmw_fastrtps_554) diff --git a/prover_rclcpp/src/rclcpp_1953.cpp b/prover_rclcpp/src/rclcpp_1953.cpp new file mode 100644 index 0000000..fa66c59 --- /dev/null +++ b/prover_rclcpp/src/rclcpp_1953.cpp @@ -0,0 +1,69 @@ +#include +#include +#include + +#include +#include +#include +#include + +using namespace std::chrono_literals; + + +/// Get current node state in a loop +void wait_for_messages(std::shared_ptr node) { + // infinite loop to receive the messages + while (rclcpp::ok()) { + std_msgs::msg::String out; + auto ret = rclcpp::wait_for_message(out, node, "chatter", 1s); + if (ret) { + RCLCPP_INFO(node->get_logger(), "WaitForMessage: [%s]", out.data.c_str()); + } else { // timeout or error + RCLCPP_INFO(node->get_logger(), "WaitForMessage: cannot receive the message"); + } + } +} + + +class TestNode : public rclcpp::Node +{ +public: + + TestNode() + : Node("test_node") + { + auto callback = [this](const std_msgs::msg::String::SharedPtr msg) -> void + { + RCLCPP_INFO(this->get_logger(), "Subscription: [%s]", msg->data.c_str()); + }; + sub_ = this->create_subscription("chatter", 10, callback); + } + + virtual ~TestNode() + { + // empty + } + +private: + rclcpp::Subscription::SharedPtr sub_; +}; + + +int main(int argc, char * argv[]) +{ + // initialize node and create subscription on it + rclcpp::init(argc, argv); + auto node = std::make_shared(); + + // create another thread to issue `wait_for_message` with TestNode object + std::thread thread_object(wait_for_messages, node); + + // give it 5 sec to make sure `wait_for_message` works + std::this_thread::sleep_for(std::chrono::seconds(5)); + + // spin the node + rclcpp::spin(node); + rclcpp::shutdown(); + + return 0; +}