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

Why does ROS overwrite my sequence number?

asked 2013-02-13 04:58:09 -0500

Max Pfingsthorn gravatar image

updated 2014-01-28 17:15:13 -0500

ngrennan gravatar image

I have noticed that the ROS Publishers seem to overwrite the sequence number set by me in the message header (std_msgs/Header). This only happens if the message is one known by ROS (such as sensor_msgs/Image) but not if it is one I defined myself.

What happens is that I set the header.seq field in e.g. the sensor_msgs/Image message to something, but during publishing, ROS overwrites this number with a counter which is apparently kept in the ros::Publisher class itself. So, when I subscribe to the message, sequence numbers of sensor_msgs/Image always start with 0 and count up by one from here, no matter what I set in the header before my call to ros::Publisher::publish().

I dug a little deeper and found that I can prevent this by using ros::AdvertiseOptions.

ros::NodeHandle n;
ros::AdvertizeOptions op = ros::AdvertiseOptions::create<sensor_msgs::Image>("/foo", 1, &connected, &disconnected, ros::VoidPtr(), NULL);
op.has_header = false;
ros::Publisher pub = n.advertise(op);

The callbacks unfortunately have to be defined, I was unable to just give NULL...

void connected(const ros::SingleSubscriberPublisher&) {}
void disconnected(const ros::SingleSubscriberPublisher&) {}

This way, my sequence numbers persist and are not overwritten by the ros::Publisher::publish() call later.

My question is, why does ROS not trust me to set the sequence number as I want it?

My test publisher:

#include <stdio.h>
#include <stdlib.h>
#include <time.h>

#include <ros ros.h="">
#include <sensor_msgs image.h="">

// dummy callbacks
void connected(const ros::SingleSubscriberPublisher&) {}
void disconnected(const ros::SingleSubscriberPublisher&) {}

int main(int argc, char** argv) {
    srand ( time(NULL) );

    ros::init(argc, argv, "test_pub");

    ros::NodeHandle n;

    ros::Publisher pub_messed_up = n.advertise<sensor_msgs::image>("/foo", 1);

    ros::AdvertiseOptions op = ros::AdvertiseOptions::create<sensor_msgs::image>("/bar", 1, &connected, &disconnected, ros::VoidPtr(), NULL);
    op.has_header = false;
    ros::Publisher pub_ok = n.advertise(op);


    ros::Rate r(1);
    while(ros::ok()) {
        sensor_msgs::Image msg;
        msg.header.seq = rand();
        msg.header.stamp = ros::Time::now();
        msg.header.frame_id = "foo";

        msg.height = msg.header.seq;

        pub_messed_up.publish(msg);
        pub_ok.publish(msg);
        r.sleep();
    }
}

My test subscriber:

#include <ros ros.h="">
#include <sensor_msgs image.h="">

void callback( const sensor_msgs::ImageConstPtr& msg ) {
    ROS_INFO("BAD: image seq is: %10u, should be %10u", msg->header.seq, msg->height);
}

void callback2( const sensor_msgs::ImageConstPtr& msg ) {
    ROS_INFO("OK : image seq is: %10u, should be %10u", msg->header.seq, msg->height);
}

int main(int argc, char** argv) {
    ros::init(argc, argv, "test_sub");

    ros::NodeHandle n;
    ros::Subscriber sub = n.subscribe("/foo", 1, &callback);
    ros::Subscriber sub2 = n.subscribe("/bar", 1, &callback2);

    ros::spin();
}

Output:

[ INFO] [1360774481.858622442]: OK : image seq is:  180403487, should be  180403487
[ INFO] [1360774481.858737733]: BAD: image seq is:          3, should be  180403487
[ INFO] [1360774481.958441959]: OK : image seq is: 1993875195, should be 1993875195
[ INFO] [1360774481.958503343]: BAD: image seq is:          4, should be 1993875195
[ INFO] [1360774482.058392020]: OK : image seq is:  458683548, should be  458683548
[ INFO] [1360774482.058461137]: BAD: image seq is:          5, should be  458683548
[ INFO] [1360774482.158405818]: OK : image seq ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
9

answered 2013-02-13 07:20:30 -0500

dornhege gravatar image

The sequence number is the sequence number of published messages. You are not supposed to change that or set that yourself as then you could only do it exactly as is or wrong (according to what it is supposed to be). This is why you can't change it nicely.

Your fix just tells ROS that there is no place (header) to store the sequence number and thus it can't supply one. If you need some unique number in your custom message, you should just define another message field.

I can't really see a use case, where you'd need to set a user-defined sequence number in an sensor_msgs/Image message that is used by a standard ROS program.

edit flag offensive delete link more

Comments

I'm working on a sensor fusion application where node A subscribes to an image stream, and outputs a pose estimate for each image. Node B also subscribes to the image stream, along with the pose estimates from node A, so it's useful if it can simply match the seq # to determine image-pose pairs.

Stephen Vidas gravatar image Stephen Vidas  ( 2013-07-18 14:11:12 -0500 )edit

If you have a sequence number, you have a header. Use the time stamp in the header to synchronize messages from the same origin. There is even a message filter that does this for you.

dornhege gravatar image dornhege  ( 2013-07-18 23:10:18 -0500 )edit
2

If ROS is so clever, why doesn't it know if a message has a header or not? Only core messages show this behavior by default, which makes it hard to track down and inconsistent. Also, this is the only thing ROS changes when I publish a message, so it's very unintuitive.

Max Pfingsthorn gravatar image Max Pfingsthorn  ( 2013-07-24 06:29:31 -0500 )edit
2

Sequence numbers were deprecated from the specification 4 years ago. But existing behavior was left for backwards compatibility. https://code.ros.org/trac/ros/ticket/1965

tfoote gravatar image tfoote  ( 2013-11-10 20:20:28 -0500 )edit
1

The link https://code.ros.org/trac/ros/ticket/... doesn't seem to be working (I'll keep searching migrated link if any).

130s gravatar image 130s  ( 2014-10-21 00:00:14 -0500 )edit
1

I still can't find the aforementiond ticket but there's an updated discussion on discourse.

130s gravatar image 130s  ( 2019-01-11 14:22:50 -0500 )edit

It seems that ROS overwrites header.seq if it is part of sensor_msgs. Publishing the same header message separately as std_msgs::Header and as part of a sensor_msgs::Pointcloud2 message, the seq field of sensor_msgs::Pointcloud2 message is overwritten by ROS whereas the seq field of std_msgs::Header is preserved.

cynosure4sure gravatar image cynosure4sure  ( 2020-07-20 07:47:23 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2013-02-13 04:58:09 -0500

Seen: 10,860 times

Last updated: Feb 13 '13