[ros-users] ROS performance - strange behaviour?

Josh Faust jfaust at willowgarage.com
Wed Aug 4 20:41:44 UTC 2010


This is almost certainly caused by Nagle's algorithm, which is used by TCP (
http://en.wikipedia.org/wiki/Nagle's_algorithm).  TCP is by default
optimized for throughput, not latency.  You can turn off Nagle's algorithm:

sub = node.subscribe<ros_perf::Blob> ("pTopic", 1024,
boost::bind(&TestNode::process, this, _1, 1)*,
ros::TransportHints().tcpNoDelay()*);

Josh

On Wed, Aug 4, 2010 at 1:27 PM, Peter Müller <grandmastermt2000 at yahoo.de>wrote:

> Hi,
>
> sorry I guess I forgot the obvious things. I am talking about roscpp
>
> Here is the code of the producer, called TestProducer:
> void TestProducer::setup()
> {
>    std::vector<uint8_t> data(10 * 1024, 1);
>    data_packet.payload = data;
>
>    connected_receiver = 0;
>
>    outStream = node.advertise<ros_perf::Blob> ("pTopic", 1024, boost::bind(
>            &TestProducer::receiverConnected, this));
> }
>
> void TestProducer::execute()
> {
>    ros::Rate loop_rate(20);
>    int current_iterations = 0;
>
>
>
>    while (ros::ok() && 1 != connected_receiver) {
>        ros::spinOnce();
>        loop_rate.sleep();
>    }
>
>
>    // no callbacks, just sending out data
>    while (ros::ok()) {
>        if (current_iterations < 10000) {
>            for(int i = 0;i < 2;++i) {
>                utility::PTime::now(data_packet.timestamp);
>                outStream.publish(data_packet);
>            }
>            ++current_iterations;
>        }
>        loop_rate.sleep();
>    }
> }
>
>
> Here is the code of the receiver, called TestNode:
> void TestNode::setup()
> {
>    sub = node.subscribe<ros_perf::Blob> ("pTopic", 1024,
> boost::bind(&TestNode::process, this, _1, 1));
> }
>
> void TestNode::execute()
> {
>    ros::spin();
> }
>
> void TestNode::process(const BlobConstPtr& msg, unsigned int index)
> {
>    double t_now = 0.0;
>    utility::PTime::now(t_now);
>
>    burst_times.push_back(msg.get()->timestamp);
>    burst_times.push_back(t_now);
> }
>
> The Blob message looks like this:
> float64 timestamp
> uint8[] payload
>
>
> The setup runs locally, so there is no problems with clockskew. PTime uses
> clock_gettime(CLOCK_REALTIME, timespec*) and should work correctly.
>
>
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20100804/1333df2e/attachment-0003.html>


More information about the ros-users mailing list