Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

suggest spin_all to migrate spinOnce to execute all available works i… (backport #4966) #4969

Merged
merged 1 commit into from
Jan 27, 2025
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -204,25 +204,29 @@ 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.

Putting it all together, the new ``talker.cpp`` looks like this:

.. code-block:: cpp

#include <chrono>
#include <sstream>
// #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");
Expand All @@ -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;
Expand Down