ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Understanding async spinner in ROS1

asked 2023-06-15 15:00:12 -0500

mudrole1 gravatar image

updated 2023-06-15 15:02:42 -0500

Hi,

so I am trying to understand async spinner in ROS1. I know ROS1 is obsolete but unfortunately, my institution is still using it...

I have noticed some weird behaviour which I would like that someone explains to me. I made a node which listens on a topic which publishes with rate 10 Hz. My callback function intentionally takes 1s to run. In the callback, I am printing the seq id of the received msg. My callback queue is just 1.

When I use ros::spin(), it is single-threaded, blocking behaviour, so I am getting msg: 1, 11, 21, 31 and so on...

When I use:

  ros::AsyncSpinner spinner(10);
  spinner.start();
  ros::waitForShutdown();

instead of ross::spin(), I would expect to see msg: 1,2,3,4,5, and so on... but I am still getting 1, 11, 21, 31 and so on... Practically it looks that the async spinner is not launching new threads. The only issue I can think off is if the sleep in my callback is somehow blocking all threads. I tried to use ros::Duration(1.0).sleep(); and std::this_thread::sleep_for (std::chrono::seconds(1)); and both gives me the same behaviour.

So can someone please tell me what I am doing wrong with the AsyncSpinner?

PS: If you wonder why my code is so silly, it is part of a bigger project, I just tried my best to strip it to necessary basics to understand the AsyncSpinner.

I am using Ubuntu 20.04 and I am running Noetic.

The code:

#include <chrono> 
#include <thread>    

#include <ros/ros.h>

#include "sensor_msgs/BatteryState.h"

void BatteryCallback(const sensor_msgs::BatteryState::ConstPtr& msg)
{
  ROS_INFO("Msg id:%d", msg->header.seq);
  //ros::Duration(1.0).sleep();
  std::this_thread::sleep_for (std::chrono::seconds(1));
}

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

  ros::Subscriber battery_sub = nh.subscribe("/fcs/battery_state", 1, BatteryCallback);

  ROS_INFO("Battery monitor is running");
  //ros::spin();
  ros::AsyncSpinner spinner(10);
  spinner.start();
  ros::waitForShutdown();
  return 0;
}

CmakeList:

cmake_minimum_required(VERSION 3.0.2)
project(battery_monitor)

find_package(catkin REQUIRED COMPONENTS
  roscpp
  sensor_msgs
)

catkin_package(
  CATKIN_DEPENDS roscpp sensor_msgs
)

include_directories(
# include
  ${catkin_INCLUDE_DIRS}
)

add_executable(battery_monitor src/battery_monitor.cpp)
target_link_libraries(battery_monitor ${catkin_LIBRARIES})

Package.xml

<?xml version="1.0"?>
<package format="2">
  <name>battery_monitor</name>
  <version>1.0.0</version>
  <description>This package ...</description>

  <maintainer email="L@M.com">L</maintainer>
  <license>MIT</license>

  <buildtool_depend>catkin</buildtool_depend>
  <build_depend>roscpp</build_depend>
  <build_depend>sensor_msgs</build_depend>

  <build_export_depend>roscpp</build_export_depend>

  <exec_depend>roscpp</exec_depend>
  <exec_depend>sensor_msgs</exec_depend>
</package>
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2023-06-15 17:22:34 -0500

Mike Scheutzow gravatar image

updated 2023-06-16 19:45:39 -0500

ROS is serializing the messages on the subscribe side. ROS is careful not to reorder messages from a publisher node. But the dispatch behavior is different between rospy and roscpp if there are multiple publishers to a topic.

For roscpp, by default, the messages received from all publishers to a topic are serialized. The messages are passed to the callback one at a time. If the queue is full, the earliest-in-time message is discarded.

For rospy, the subscribe side is taking both the publisher node and topic name into account. Messages arriving from a particular publisher node are queued and passed to the callback in order, but rospy will execute the callback in parallel to process multiple messages on a topic if they are from different publisher nodes.

Update: rewrote this answer to clarify that rospy and roscpp can have different behavior. For roscpp, @gvdhoorn points out in the comments that it's possible to change the default behavior to request parallel execution of the callback.

edit flag offensive delete link more

Comments

Maybe, I need to add how do I test my node - I just publish topic from terminal where the header seq id (the one which I care) is increased automatically. When I echo the published topic, I see the msg are being published as 1,2,3,4, etc... Here the problem is that the async spinner seems not to spawn any new threads and behaves exactly the same as ros::spin()

Just in case, here is my testing command:

rostopic pub -r 10 /fcs/battery_state sensor_msgs/BatteryState "header:
  seq: 0
  stamp: {secs: 0, nsecs: 0}
  frame_id: ''
voltage: 0.0
temperature: 0.0
current: 0.0
charge: 0.0
capacity: 0.0
design_capacity: 0.0
percentage: 0.0
power_supply_status: 0
power_supply_health: 0
power_supply_technology: 0
present: false
cell_voltage: [0]
cell_temperature: [0]
location: ''
serial_number: ''"
mudrole1 gravatar image mudrole1  ( 2023-06-16 08:19:33 -0500 )edit

What I believe @Mike Scheutzow is referring to is this behaviour (from here):

By default subscription callbacks are guaranteed to arrive in-order, with only one callback happening for this subscription at any given time.

So even with a MultiThreadedSpinner or an AsyncSpinner, you will not see concurrent processing of callbacks for messages coming in on a single topic (or: via a single subscriber).

If you want to allow messages for a specific subscription to be handled by different threads, you could set SubscribeOptions::allow_concurrent_callbacks to true:

ros::SubscribeOptions ops;
ops.init<sensor_msgs/BatteryState>("/fcs/battery_state", 1, BatteryCallback);
ops.allow_concurrent_callbacks = true;
ros::Subscriber battery_sub = n.subscribe(ops);

(haven't compiled this, there could be syntax errors)

gvdhoorn gravatar image gvdhoorn  ( 2023-06-16 08:43:04 -0500 )edit

Please note that setting allow_concurrent_callbacks removes the 'guarantee' that callbacks will happen in-order. If ordering of messages is important, allow_concurrent_callbacks = true might not be a good idea.

And normally I wouldn't do this (ie: link to an external resource), but this is a pretty good article which goes into the details of roscpp's threading model: ROS Spinning, Threading, Queuing. It discusses something similar right above the Multi Callback queues section.

Note that what you describe would appear to be due to loss of messages as the incoming stream is not being processed fast enough. You configure a queue_size of only 1, which might not be sufficient for the rate at which new messages are coming in.

gvdhoorn gravatar image gvdhoorn  ( 2023-06-16 08:45:50 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2023-06-15 15:00:12 -0500

Seen: 604 times

Last updated: Jun 16 '23