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

ROS2 migration guide replaces spinOnce with spin_some #4959

Closed
wouter-heerwegh opened this issue Jan 23, 2025 · 12 comments · Fixed by #4966
Closed

ROS2 migration guide replaces spinOnce with spin_some #4959

wouter-heerwegh opened this issue Jan 23, 2025 · 12 comments · Fixed by #4966
Assignees
Labels
bug Something isn't working good first issue Good for newcomers help wanted Extra attention is needed

Comments

@wouter-heerwegh
Copy link

I recently stumbled on an issue where I was using spin_some in a node that was receiving messages at a higher rate than it was calling the spin_some function. After a bunch of digging, I found the following issue on rclcpp ros2/rclcpp#2655, which mentions that spin_some only processes 1 message of each callback, rather then all work on all callbacks at that time.

It seems that spin_all functionality more closely resembles the spinOnce behaviour from ROS1.

My code was converted according to the migration guide, so I think it would be best to change the example to use spin_all instead

@kscottz
Copy link
Collaborator

kscottz commented Jan 23, 2025

@wouter-heerwegh thanks for reporting this.

@fujitatomoya I want a quick second opinion, does this sound like a reasonable request? If the answer is yes I can put together a PR.

Somewhat related, the spin_all API documentation could use some love and this might warrant a second ticket.

@kscottz kscottz added help wanted Extra attention is needed good first issue Good for newcomers labels Jan 23, 2025
@fujitatomoya
Copy link
Collaborator

@kscottz i guess, some semantic for them are different from ROS 1 to ROS 2, but including that i will check to see if the doc or implementation needs to be updated. i will take a look.

@fujitatomoya fujitatomoya self-assigned this Jan 23, 2025
@ros-discourse
Copy link

This issue has been mentioned on ROS Discourse. There might be relevant details there:

https://discourse.ros.org/t/ros-news-for-the-week-of-january-20th-2025/41719/1

@fujitatomoya
Copy link
Collaborator

@wouter-heerwegh

spin_some only processes 1 message of each callback, rather then all work on all callbacks at that time.

precisely spin_some can process a data for each entity. (if 2 subscriptions are data-ready, it calls both user callbacks.)

IMO, the doc section is not well described... i would expect that all ready data in the single entity will be executed. that is the claim from ros2/rclcpp#2655.

https://github.com/ros2/rclcpp/blob/2d1b770e858fdb20e9c25913341fb388100dd19e/rclcpp/include/rclcpp/executor.hpp#L283-L303

It seems that spin_all functionality more closely resembles the spinOnce behaviour from ROS1.

I do not think so.

https://docs.ros.org/en/diamondback/api/roscpp/html/namespaceros.html#af4afa6f0ad9f903f04a023982a95ff1c says Process a single round of callbacks and processes only one message from each callback queue in the node handle's associated callback queue during a single call. If you have two subscriptions and call ros::spinOnce() once, it will process only one callback per subscription (if messages are available for both).

that said, ros::spinOnce() matches to Executor::spin_some, not Executor::spin_all.

after all, i think migration doc is correct. what do you think?

@wouter-heerwegh
Copy link
Author

wouter-heerwegh commented Jan 24, 2025

@fujitatomoya
Thanks for the reply.

While it's definitely documented as such, I think the behaviour is slightly different. When I check the implementation of spinOnce in the roscpp documentation, it seems to call callAvailable. And that function is documented as if it would process all callbacks. So it looks a bit like spin_all with a timeout of 0.

I'll make a small subscriber and publisher node to test the behaviour in ROS1, just to confirm.

@kscottz
Copy link
Collaborator

kscottz commented Jan 24, 2025

I think the real issue here, as show by this issue and #2655, is that the behavior of spin, spin_some, and spin_all isn't self-evident and the API docs don't really clarify the difference.

Regardless of where we land on this particular problem, we probably want to improve the API documentation and write a guide explaining when to use each variant of spin.

@fujitatomoya
Copy link
Collaborator

I'll make a small subscriber and publisher node to test the behaviour in ROS1, just to confirm.

that definitely helps here 🚀 thanks!

@wouter-heerwegh
Copy link
Author

@fujitatomoya, I did the following tests:

  • ROS1 spinOnce implementation
  • ROS2 spin_some implementation
  • ROS2 spin_all implementation with 0 max_duration
  • ROS2 spin_all implementation with 5s max_duration

ROS1 spinOnce

Subscriber

#include "ros/ros.h"
#include "std_msgs/String.h"

ros::Time last_msg_time;

void chatterCallback(const std_msgs::String::ConstPtr &msg)
{
	ROS_INFO_STREAM("I heard: [" << msg->data.c_str() << "], time offset: " << (ros::Time::now() - last_msg_time).toSec());
	last_msg_time = ros::Time::now();
}

int main(int argc, char **argv)
{
	ros::init(argc, argv, "listener");
	ros::NodeHandle n;

	ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);
	last_msg_time = ros::Time::now();
	ros::Rate loop_rate(0.2);
	while(ros::ok())
	{
		ros::spinOnce();
		loop_rate.sleep();
		ROS_INFO_STREAM("Looping...");
	}

	return 0;
}

Publisher

#include "ros/ros.h"
#include "std_msgs/String.h"

#include <sstream>

int main(int argc, char **argv)
{
  ros::init(argc, argv, "talker");
  ros::NodeHandle n;
  ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);

  ros::Rate loop_rate(1);

  int count = 0;
  while (ros::ok())
  {
    std_msgs::String msg;

    std::stringstream ss;
    ss << "hello world " << count;
    msg.data = ss.str();

    ROS_INFO("%s", msg.data.c_str());

    chatter_pub.publish(msg);

    ros::spinOnce();

    loop_rate.sleep();
    ++count;
  }


  return 0;
}

Logs

Subscriber

[ INFO] [1737834045.782031480]: Looping...
[ INFO] [1737834045.783269793]: I heard: [hello world 2], time offset: 5.00143
[ INFO] [1737834045.783297436]: I heard: [hello world 3], time offset: 8.154e-06
[ INFO] [1737834045.783313897]: I heard: [hello world 4], time offset: 3.85e-06
[ INFO] [1737834045.783329191]: I heard: [hello world 5], time offset: 3.653e-06
[ INFO] [1737834050.781920524]: Looping...
[ INFO] [1737834050.781993415]: I heard: [hello world 6], time offset: 4.99864
[ INFO] [1737834050.782013652]: I heard: [hello world 7], time offset: 6.494e-06
[ INFO] [1737834050.782031139]: I heard: [hello world 8], time offset: 3.906e-06
[ INFO] [1737834050.782046394]: I heard: [hello world 9], time offset: 3.654e-06
[ INFO] [1737834050.782070624]: I heard: [hello world 10], time offset: 3.964e-06
[ INFO] [1737834055.781920046]: Looping...
[ INFO] [1737834055.781991065]: I heard: [hello world 11], time offset: 4.9999
[ INFO] [1737834055.782011320]: I heard: [hello world 12], time offset: 5.853e-06
[ INFO] [1737834055.782026733]: I heard: [hello world 13], time offset: 4.219e-06
[ INFO] [1737834055.782042235]: I heard: [hello world 14], time offset: 3.758e-06
[ INFO] [1737834055.782058199]: I heard: [hello world 15], time offset: 3.825e-06

Publisher

[ INFO] [1737834040.022939559]: hello world 0
[ INFO] [1737834041.023097018]: hello world 1
[ INFO] [1737834042.023093220]: hello world 2
[ INFO] [1737834043.023086358]: hello world 3
[ INFO] [1737834044.023091466]: hello world 4
[ INFO] [1737834045.023085239]: hello world 5
[ INFO] [1737834046.022987949]: hello world 6
[ INFO] [1737834047.023089965]: hello world 7
[ INFO] [1737834048.023088516]: hello world 8
[ INFO] [1737834049.023088847]: hello world 9
[ INFO] [1737834050.023094621]: hello world 10
[ INFO] [1737834051.023087304]: hello world 11
[ INFO] [1737834052.023084743]: hello world 12
[ INFO] [1737834053.023015742]: hello world 13
[ INFO] [1737834054.023089233]: hello world 14
[ INFO] [1737834055.023087920]: hello world 15
[ INFO] [1737834056.023088054]: hello world 16
[ INFO] [1737834057.023070945]: hello world 17

ROS2 spin_some

Subscriber

#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

class MinimalSubscriber : public rclcpp::Node
{
public:
	MinimalSubscriber()
		: Node("minimal_subscriber")
	{
		auto topic_callback =
			[this](std_msgs::msg::String::UniquePtr msg) -> void
		{
			RCLCPP_INFO_STREAM(this->get_logger(), "I heard:  [" << msg->data.c_str() << "], time offset: " << (this->now() - last_msg_time).seconds());
			last_msg_time = this->now();
		};
		subscription_ =
			this->create_subscription<std_msgs::msg::String>("topic", 10, topic_callback);
	}

private:
	rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
	rclcpp::Time last_msg_time = this->now();
};

int main(int argc, char *argv[])
{
	rclcpp::init(argc, argv);
	rclcpp::Node::SharedPtr node = std::make_shared<MinimalSubscriber>();

	rclcpp::Rate rate(0.2);
	while(rclcpp::ok())
	{
		rclcpp::spin_some(node);
		rate.sleep();
	}
	rclcpp::shutdown();
	return 0;
}

Publisher

#include <chrono>
#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

using namespace std::chrono_literals;

class MinimalPublisher : public rclcpp::Node
{
public:
  MinimalPublisher()
  : Node("minimal_publisher"), count_(0)
  {
    publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
    auto timer_callback =
      [this]() -> void {
        auto message = std_msgs::msg::String();
        message.data = "Hello, world! " + std::to_string(this->count_++);
        RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
        this->publisher_->publish(message);
      };
    timer_ = this->create_wall_timer(1s, timer_callback);
  }

private:
  rclcpp::TimerBase::SharedPtr timer_;
  rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
  size_t count_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalPublisher>());
  rclcpp::shutdown();
  return 0;
}

Logs

Subscriber

[INFO] [1737834880.191859878] [minimal_subscriber]: I heard:  [Hello, world! 0], time offset: 5.00116
[INFO] [1737834885.191631001] [minimal_subscriber]: I heard:  [Hello, world! 1], time offset: 4.99945
[INFO] [1737834890.191673289] [minimal_subscriber]: I heard:  [Hello, world! 3], time offset: 4.99987
[INFO] [1737834895.191528547] [minimal_subscriber]: I heard:  [Hello, world! 8], time offset: 4.99969

Publisher

[INFO] [1737834877.835697109] [minimal_publisher]: Publishing: 'Hello, world! 0'
[INFO] [1737834878.835733196] [minimal_publisher]: Publishing: 'Hello, world! 1'
[INFO] [1737834879.835728231] [minimal_publisher]: Publishing: 'Hello, world! 2'
[INFO] [1737834880.835719712] [minimal_publisher]: Publishing: 'Hello, world! 3'
[INFO] [1737834881.835727291] [minimal_publisher]: Publishing: 'Hello, world! 4'
[INFO] [1737834882.835718983] [minimal_publisher]: Publishing: 'Hello, world! 5'
[INFO] [1737834883.835714153] [minimal_publisher]: Publishing: 'Hello, world! 6'
[INFO] [1737834884.835789483] [minimal_publisher]: Publishing: 'Hello, world! 7'
[INFO] [1737834885.835694499] [minimal_publisher]: Publishing: 'Hello, world! 8'
[INFO] [1737834886.835747686] [minimal_publisher]: Publishing: 'Hello, world! 9'
[INFO] [1737834887.835617868] [minimal_publisher]: Publishing: 'Hello, world! 10'
[INFO] [1737834888.835585636] [minimal_publisher]: Publishing: 'Hello, world! 11'
[INFO] [1737834889.835582015] [minimal_publisher]: Publishing: 'Hello, world! 12'
[INFO] [1737834890.835567956] [minimal_publisher]: Publishing: 'Hello, world! 13'
[INFO] [1737834891.835565611] [minimal_publisher]: Publishing: 'Hello, world! 14'
[INFO] [1737834892.835584229] [minimal_publisher]: Publishing: 'Hello, world! 15'
[INFO] [1737834893.835586867] [minimal_publisher]: Publishing: 'Hello, world! 16'
[INFO] [1737834894.835632711] [minimal_publisher]: Publishing: 'Hello, world! 17'
[INFO] [1737834895.835634136] [minimal_publisher]: Publishing: 'Hello, world! 18'
[INFO] [1737834896.835754409] [minimal_publisher]: Publishing: 'Hello, world! 19'
[INFO] [1737834897.835636473] [minimal_publisher]: Publishing: 'Hello, world! 20'
[INFO] [1737834898.835495235] [minimal_publisher]: Publishing: 'Hello, world! 21'

ROS2 spin_all with 0 max_duration

Same code for subscriber and publisher except spin_some converted to spin_all with 0s max_duration

Logs

Subscriber

[INFO] [1737835532.499158089] [minimal_subscriber]: I heard:  [Hello, world! 0], time offset: 5.00109
[INFO] [1737835532.499537772] [minimal_subscriber]: I heard:  [Hello, world! 1], time offset: 8.1787e-05
[INFO] [1737835532.499607355] [minimal_subscriber]: I heard:  [Hello, world! 2], time offset: 3.602e-05
[INFO] [1737835537.498975759] [minimal_subscriber]: I heard:  [Hello, world! 3], time offset: 4.99933
[INFO] [1737835537.499178449] [minimal_subscriber]: I heard:  [Hello, world! 4], time offset: 4.7761e-05
[INFO] [1737835537.499232779] [minimal_subscriber]: I heard:  [Hello, world! 5], time offset: 2.6296e-05
[INFO] [1737835537.499279745] [minimal_subscriber]: I heard:  [Hello, world! 6], time offset: 2.4066e-05
[INFO] [1737835537.499326932] [minimal_subscriber]: I heard:  [Hello, world! 7], time offset: 2.5614e-05
[INFO] [1737835542.498988283] [minimal_subscriber]: I heard:  [Hello, world! 8], time offset: 4.99961
[INFO] [1737835542.499184180] [minimal_subscriber]: I heard:  [Hello, world! 9], time offset: 4.81e-05
[INFO] [1737835542.499236934] [minimal_subscriber]: I heard:  [Hello, world! 10], time offset: 2.6888e-05
[INFO] [1737835542.499282934] [minimal_subscriber]: I heard:  [Hello, world! 11], time offset: 2.5081e-05
[INFO] [1737835542.499326954] [minimal_subscriber]: I heard:  [Hello, world! 12], time offset: 2.5729e-05
[INFO] [1737835547.498624013] [minimal_subscriber]: I heard:  [Hello, world! 13], time offset: 4.99927
[INFO] [1737835547.498682507] [minimal_subscriber]: I heard:  [Hello, world! 14], time offset: 1.0196e-05
[INFO] [1737835547.498690532] [minimal_subscriber]: I heard:  [Hello, world! 15], time offset: 4.115e-06

Publisher

[INFO] [1737835530.191950924] [minimal_publisher]: Publishing: 'Hello, world! 0'
[INFO] [1737835531.191982235] [minimal_publisher]: Publishing: 'Hello, world! 1'
[INFO] [1737835532.192049901] [minimal_publisher]: Publishing: 'Hello, world! 2'
[INFO] [1737835533.191933634] [minimal_publisher]: Publishing: 'Hello, world! 3'
[INFO] [1737835534.191984099] [minimal_publisher]: Publishing: 'Hello, world! 4'
[INFO] [1737835535.191987575] [minimal_publisher]: Publishing: 'Hello, world! 5'
[INFO] [1737835536.191990439] [minimal_publisher]: Publishing: 'Hello, world! 6'
[INFO] [1737835537.191984811] [minimal_publisher]: Publishing: 'Hello, world! 7'
[INFO] [1737835538.192005315] [minimal_publisher]: Publishing: 'Hello, world! 8'
[INFO] [1737835539.192008494] [minimal_publisher]: Publishing: 'Hello, world! 9'
[INFO] [1737835540.191980526] [minimal_publisher]: Publishing: 'Hello, world! 10'
[INFO] [1737835541.191937971] [minimal_publisher]: Publishing: 'Hello, world! 11'
[INFO] [1737835542.192004791] [minimal_publisher]: Publishing: 'Hello, world! 12'
[INFO] [1737835543.191945028] [minimal_publisher]: Publishing: 'Hello, world! 13'
[INFO] [1737835544.192020682] [minimal_publisher]: Publishing: 'Hello, world! 14'
[INFO] [1737835545.191938151] [minimal_publisher]: Publishing: 'Hello, world! 15'

ROS2 spin_all with 5s max_duration

Same code for subscriber and publisher except spin_some converted to spin_all with 5s max_duration

Logs

Subscriber

[INFO] [1737835723.111208161] [minimal_subscriber]: I heard:  [Hello, world! 0], time offset: 5.00102
[INFO] [1737835723.111559488] [minimal_subscriber]: I heard:  [Hello, world! 1], time offset: 5.2333e-05
[INFO] [1737835723.111617613] [minimal_subscriber]: I heard:  [Hello, world! 2], time offset: 2.6683e-05
[INFO] [1737835728.111121631] [minimal_subscriber]: I heard:  [Hello, world! 3], time offset: 4.99946
[INFO] [1737835728.111297446] [minimal_subscriber]: I heard:  [Hello, world! 4], time offset: 4.0458e-05
[INFO] [1737835728.111350177] [minimal_subscriber]: I heard:  [Hello, world! 5], time offset: 2.2942e-05
[INFO] [1737835728.111398654] [minimal_subscriber]: I heard:  [Hello, world! 6], time offset: 2.775e-05
[INFO] [1737835728.111442170] [minimal_subscriber]: I heard:  [Hello, world! 7], time offset: 2.3742e-05
[INFO] [1737835733.111150714] [minimal_subscriber]: I heard:  [Hello, world! 8], time offset: 4.99966
[INFO] [1737835733.111364230] [minimal_subscriber]: I heard:  [Hello, world! 9], time offset: 4.8373e-05
[INFO] [1737835733.111419343] [minimal_subscriber]: I heard:  [Hello, world! 10], time offset: 2.7058e-05
[INFO] [1737835733.111466060] [minimal_subscriber]: I heard:  [Hello, world! 11], time offset: 2.4837e-05
[INFO] [1737835733.111509427] [minimal_subscriber]: I heard:  [Hello, world! 12], time offset: 2.5222e-05
[INFO] [1737835738.111116033] [minimal_subscriber]: I heard:  [Hello, world! 13], time offset: 4.99956
[INFO] [1737835738.111320576] [minimal_subscriber]: I heard:  [Hello, world! 14], time offset: 5.1276e-05
[INFO] [1737835738.111377321] [minimal_subscriber]: I heard:  [Hello, world! 15], time offset: 2.6335e-05
[INFO] [1737835738.111461587] [minimal_subscriber]: I heard:  [Hello, world! 16], time offset: 2.4741e-05
[INFO] [1737835738.111508974] [minimal_subscriber]: I heard:  [Hello, world! 17], time offset: 2.4794e-05

Publisher

[INFO] [1737835720.997993174] [minimal_publisher]: Publishing: 'Hello, world! 0'
[INFO] [1737835721.997991028] [minimal_publisher]: Publishing: 'Hello, world! 1'
[INFO] [1737835722.998115940] [minimal_publisher]: Publishing: 'Hello, world! 2'
[INFO] [1737835723.998086001] [minimal_publisher]: Publishing: 'Hello, world! 3'
[INFO] [1737835724.997963379] [minimal_publisher]: Publishing: 'Hello, world! 4'
[INFO] [1737835725.998044965] [minimal_publisher]: Publishing: 'Hello, world! 5'
[INFO] [1737835726.998007839] [minimal_publisher]: Publishing: 'Hello, world! 6'
[INFO] [1737835727.998002223] [minimal_publisher]: Publishing: 'Hello, world! 7'
[INFO] [1737835728.998010047] [minimal_publisher]: Publishing: 'Hello, world! 8'
[INFO] [1737835729.997992773] [minimal_publisher]: Publishing: 'Hello, world! 9'
[INFO] [1737835730.997988944] [minimal_publisher]: Publishing: 'Hello, world! 10'
[INFO] [1737835731.997993312] [minimal_publisher]: Publishing: 'Hello, world! 11'
[INFO] [1737835732.997991355] [minimal_publisher]: Publishing: 'Hello, world! 12'
[INFO] [1737835733.998011520] [minimal_publisher]: Publishing: 'Hello, world! 13'
[INFO] [1737835734.998001647] [minimal_publisher]: Publishing: 'Hello, world! 14'
[INFO] [1737835735.997984794] [minimal_publisher]: Publishing: 'Hello, world! 15'
[INFO] [1737835736.998004819] [minimal_publisher]: Publishing: 'Hello, world! 16'
[INFO] [1737835737.998000897] [minimal_publisher]: Publishing: 'Hello, world! 17'
[INFO] [1737835738.998006518] [minimal_publisher]: Publishing: 'Hello, world! 18'
[INFO] [1737835739.998002386] [minimal_publisher]: Publishing: 'Hello, world! 19'
[INFO] [1737835740.997965316] [minimal_publisher]: Publishing: 'Hello, world! 20'
[INFO] [1737835741.997967480] [minimal_publisher]: Publishing: 'Hello, world! 21'
[INFO] [1737835742.997893886] [minimal_publisher]: Publishing: 'Hello, world! 22'

Conclusion

From these tests it does look as if spin_all is more closely resembling the spinOnce behaviour.

@fujitatomoya
Copy link
Collaborator

From these tests it does look as if spin_all is more closely resembling the spinOnce behaviour.

@wouter-heerwegh thank you very much for confirming this! and based on this result, i agree with you conclusion.

there is a couple of things that i need to do,

  • i will check if this ROS 2 rclcpp::spin_some behavior is by design with other maintainers. if not, we need to fix rclcpp::spin_some implementation. otherwise, we need to update the doc section to clarify the behavior.
  • even though rclcpp::spin_some needs to be fixed, current migration is not correct for user at this moment. ROS 1 spinOnce should be replaced with ROS 2 rclcpp::spin_some as we confirmed here.

@fujitatomoya
Copy link
Collaborator

@wouter-heerwegh @kscottz

could you take a look at #4966?

@wouter-heerwegh
Copy link
Author

Looks good to me, I guess another issue should be opened to keep track of a more elaborate part of the documentation explaining the differences between the spin methods, right?

If some help is needed, I would gladly help out.

@fujitatomoya
Copy link
Collaborator

thanks!

I guess another issue should be opened to keep track of a more elaborate part of the documentation explaining the differences between the spin methods, right?

i can do that once i confirm the designed behavior.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working good first issue Good for newcomers help wanted Extra attention is needed
Projects
None yet
Development

Successfully merging a pull request may close this issue.

4 participants