ros / ros_comm

ROS communications-related packages, including core client libraries (roscpp, rospy, roslisp) and graph introspection tools (rostopic, rosnode, rosservice, rosparam).
http://wiki.ros.org/ros_comm
752 stars 913 forks source link

Does subscriber drop message according to message size? #2213

Closed TaoYibo1866 closed 2 years ago

TaoYibo1866 commented 2 years ago

I have two nodes, "publisher" and "subscriber". The 'publisher' publishes ByteMultiArray messages in 50Hz, with "queue_size=1". The "subscriber" subscribes to the 50Hz topic with "queue_size=1", and publishes output in the callback function.

When the ByteMultiArray message is less than 508 bytes, everything goes as expected and the callback function is executed in 50Hz. However, when the message is bigger than 508 bytes, callback frequency drops to 28Hz. This is wired.

publisher.cpp

#include <ros/ros.h>
#include <std_msgs/ByteMultiArray.h>

using std_msgs::ByteMultiArray;

int main(int argc, char **argv)
{
  ros::init(argc, argv, "publisher");
  ros::NodeHandle nh;
  ros::Publisher bytes_pub = nh.advertise<ByteMultiArray>("bytes", 1);
  ros::Rate r(50);
  while (ros::ok())
  {
    ByteMultiArray msg;
    msg.data.resize(508);
    bytes_pub.publish(msg);
    ros::spinOnce();
    r.sleep();
  }
  return 0;
}

subscriber.cpp

#include <ros/ros.h>
#include <std_msgs/ByteMultiArray.h>
#include <std_msgs/Empty.h>

using std_msgs::ByteMultiArray;
using std_msgs::Empty;

void odomCb(ByteMultiArray msg)
{
  static ros::NodeHandle nh;
  static ros::Publisher pub = nh.advertise<Empty>("callback", 1);
  Empty empty;
  pub.publish(empty);
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "subscriber");
  ros::NodeHandle nh;
  ros::Subscriber bytes_sub = nh.subscribe<ByteMultiArray>("bytes", 1, odomCb);
  ros::spin();
  return 0;
}

rostopic hz /callback

subscribed to [/callback] average rate: 30.048 min: 0.000s max: 0.044s std dev: 0.01621s window: 29 average rate: 28.119 min: 0.000s max: 0.048s std dev: 0.01442s window: 56 average rate: 27.588 min: 0.000s max: 0.048s std dev: 0.01386s window: 82 average rate: 27.553 min: 0.000s max: 0.048s std dev: 0.01376s window: 110 average rate: 27.373 min: 0.000s max: 0.048s std dev: 0.01351s window: 136

rostopic hz /bytes

subscribed to [/bytes] average rate: 49.993 min: 0.000s max: 0.048s std dev: 0.01723s window: 50 average rate: 49.997 min: 0.000s max: 0.048s std dev: 0.01895s window: 99 average rate: 49.999 min: 0.000s max: 0.048s std dev: 0.01949s window: 150 average rate: 49.974 min: 0.000s max: 0.048s std dev: 0.01980s window: 199

TaoYibo1866 commented 2 years ago

My machine is running Ubuntu 20.04, ROS Noetic.

TaoYibo1866 commented 2 years ago

Using ros::Subscriber bytes_sub = nh.subscribe<ByteMultiArray>("bytes", 1, odomCb, ros::TransportHints().tcpNoDelay()); fix message drop. Still wonder why though.