From be8414b923885870c0984dc746c0d357e876a7de Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Mon, 27 Jan 2025 00:45:43 -0800 Subject: [PATCH] suggest spin_all to migrate spinOnce to execute all available works in the queue. (#4966) Signed-off-by: Tomoya.Fujita (cherry picked from commit 482b754eba5d8bc071b62f45029cf46d2e6fa404) --- .../Migrating-CPP-Package-Example.rst | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Package-Example.rst b/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Package-Example.rst index 5cdb8ff0ccf..f380f55e3b8 100644 --- a/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Package-Example.rst +++ b/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Package-Example.rst @@ -204,13 +204,13 @@ Change the publish call to use the ``->`` operator instead of ``.``. chatter_pub->publish(msg); Spinning (i.e., letting the communications system process any pending -incoming/outgoing messages) is different in that the call now takes the node as -an argument: +incoming/outgoing messages until no more work is available) is different +in that the call now takes the node and timeout as arguments: .. code-block:: cpp // ros::spinOnce(); - rclcpp::spin_some(node); + rclcpp::spin_all(node, 0s); Sleeping using the rate object is unchanged. @@ -218,11 +218,15 @@ Putting it all together, the new ``talker.cpp`` looks like this: .. code-block:: cpp + #include #include // #include "ros/ros.h" #include "rclcpp/rclcpp.hpp" // #include "std_msgs/String.h" #include "std_msgs/msg/string.hpp" + + using namespace std::chrono_literals; + int main(int argc, char **argv) { // ros::init(argc, argv, "talker"); @@ -247,7 +251,7 @@ Putting it all together, the new ``talker.cpp`` looks like this: // chatter_pub.publish(msg); chatter_pub->publish(msg); // ros::spinOnce(); - rclcpp::spin_some(node); + rclcpp::spin_all(node, 0s); loop_rate.sleep(); } return 0;