[ros-users] Latency of subscriber callback for large amount of data

Kim, Yoonsoo yesarang.kim at gmail.com
Wed Oct 12 03:25:06 UTC 2011


Hi, ROS users,

I'm trying to send large amount of data like image data with 100hz through
topic messages.
But it seems that subscriber callback is called 4 times in a batch in 25hz
at maximum.
I've managed to reproduce this problem with the following simple code.

-- publisher start --
#include <iostream>
#include <fstream>
#include <boost/date_time.hpp>
#include <ros/ros.h>
#include <ros/console.h>
#include <std_msgs/String.h>
#include <sstream>

using namespace std;

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(100);
  int count = 0;
  while (ros::ok() && count < 2000) {
    std_msgs::String msg;
    std::stringstream ss;
    for (int i = 0; i < 100; ++i) {                // to make large amount
of data
      ss << "hello world " << count;
    }
    msg.data = ss.str();
    chatter_pub.publish(msg);

    ros::spinOnce();
    loop_rate.sleep();
    ++count;
  }

  return 0;
}
-- publisher end --

-- subscriber start --
#include <boost/date_time.hpp>
#include <ros/ros.h>
#include <ros/callback_queue.h>
#include <ros/console.h>
#include <std_msgs/String.h>
#include <sstream>

using namespace std;

boost::posix_time::ptime curTime;
boost::posix_time::ptime prevTime;

void printLogTime() {
  curTime = boost::posix_time::microsec_clock::local_time();
  boost::posix_time::time_duration td = curTime - prevTime;
  cout << td.total_microseconds() << endl;
  prevTime = curTime;
}

void chatterCallback(const std_msgs::String::ConstPtr& msg) {
  printLogTime();
}

int main(int argc, char **argv) {
  ros::init(argc, argv, "listener");
  ros::NodeHandle n;
  ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);
  ros::spin();

  return 0;
}
-- subscriber end --

Subscriber's console log is as follows
---
9223372036854775806
9911
9986
9996
10001
10002
9995
9999
10002
10017
9988
9994
10000
10002
9998
10002
10000
9993
*39598*
*28*
*38*
*39932*
*28*
*47*
*23*
*39900*
*28*
*45*
*24*
*39906*
*26*
*46*
*23*
*39903*
*26*
*48*
*24*
---

As you can see, subscriber callback is called as expected, but is called 4
times in a batch
after sometime.

If I change ros::spin() as follows,

--- alternate loop --
  ros::Rate r(100);
  while (ros::ok()) {
    r.sleep();
    ros::getGlobalCallbackQueue()->callOne(ros::WallDuration(0.001));
  }
---

then, this problem does not happen.

subscriber's log with alternate loop
---
9223372036854775806
9905
9992
10008
9993
9997
10004
9997
10001
10000
10004
9998
9995
10009
9997
9998
10014
9998
9999
10000
10005
9997
9995
10010
9995
9999
10002
10000
9994
10002
10004
9998
10000
10007
9991
10002
10001
9999
9997
10000
10006
9997
10010
9991
9998
10000
10002
9999
9997
9999
10006
9998
9999
10001
10001
9998
9999
...
---

"rostopic hz" command also suffers from this problem.
---
$ rostopic hz /chatter
subscribed to [/chatter]
average rate: 98.983
        *min: 0.000s max: 0.040s* std dev: 0.01574s window: 97
average rate: 99.500
        *min: 0.000s max: 0.040s* std dev: 0.01654s window: 197
average rate: 99.668
        *min: 0.000s max: 0.040s* std dev: 0.01680s window: 297
average rate: 99.755
        *min: 0.000s max: 0.040s* std dev: 0.01692s window: 397
average rate: 99.807
        *min: 0.000s max: 0.040s* std dev: 0.01699s window: 497
average rate: 99.839
        *min: 0.000s max: 0.040s* std dev: 0.01704s window: 597
---

Periodic transmission of topic messages with strong timing constraints is
important
for my application but the 'alternate loop' solution doesn't allow me to use
different hz
between publisher and subscriber, which is not a perfect solution for my
application.

Is there any way to adjust latency of subscriber callback?

Thanks a lot!

- Yoonsoo
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.osuosl.org/pipermail/ros-users/attachments/20111012/e4cc0b58/attachment-0003.html>


More information about the ros-users mailing list