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

Issues with header seq value (first value in rospy is 1, first value in roscpp is 0, access from roscpp)

asked 2016-10-21 17:31:27 -0500

sd1074 gravatar image

updated 2016-10-29 19:37:31 -0500

I was planning to use Header seq value to verify that communication in my system of ROS-nodes (using ROS Indigo) is synchronized, however, I discovered a couple issues with that value. If that's a bug, I guess I can submit it to the ROS issue tracker.

  1. The value of seq in the first message published with a rospy node is 1, whereas the value of seq in the same case with roscpp node is 0 (see examples below). That looks somewhat inconsistent. Is that an expected behavior or a bug?
  2. In rospy, msg.header.seq is updated every time the message is published. In roscpp, in the published data the value is incremented as well, but the value in the message object itself doesn't seem to be updated (always 0). How to actually read that value?

Python example

First, let's take a look at a slightly modified talker example from the tutorials:

#!/usr/bin/env python
import rospy
from geometry_msgs.msg import PoseStamped

def talker():
    pub = rospy.Publisher('chatter', PoseStamped, queue_size=1000)
    rospy.init_node('talker', anonymous=True)
    rospy.sleep(10) # just to ensure we don't miss any messages with rostopic echo
    rate = rospy.Rate(1)
    msg = PoseStamped()
    while not rospy.is_shutdown():
        pub.publish(msg)
        rospy.loginfo("seq=%d" % msg.header.seq)
        rate.sleep()

if __name__ == '__main__':
    try:
        talker()
    except rospy.ROSInterruptException:
        pass

The output of the node is:

$ rosrun my_pkg chatter.py
[INFO] [WallTime: 1477087924.109463] seq=1
[INFO] [WallTime: 1477087925.110565] seq=2
[INFO] [WallTime: 1477087926.110574] seq=3

And the output of rostopic echo /chatter/header/seq is:

$ rostopic echo /chatter/header/seq
1
---
2
---
3
---

C++ example

Now a seemingly equivalent c++ node:

#include "ros/ros.h"
#include "geometry_msgs/PoseStamped.h"

int main(int argc, char **argv) {
    ros::init(argc, argv, "talker");
    ros::NodeHandle n;
    ros::Publisher chatter_pub = n.advertise<geometry_msgs::PoseStamped>("chatter", 1000);
    ros::Rate loop_rate(1);
    ros::Duration(5).sleep();
    geometry_msgs::PoseStamped msg;
    while (ros::ok())  {
        chatter_pub.publish(msg);
        ros::spinOnce();
        ROS_INFO("seq=%d", msg.header.seq);
        loop_rate.sleep();
    }
    return 0;
}

The output of the node is:

$ rosrun my_pkg chatter
[ INFO] [1477088294.353026135]: seq=0
[ INFO] [1477088294.353167359]: seq=0
[ INFO] [1477088295.353267882]: seq=0

And the output of rostopic echo /chatter/header/seq is:

$ rostopic echo /chatter/header/seq
0
---
1
---
2
---
edit retag flag offensive close merge delete

Comments

I submitted this issue to ros_comm tracker: https://github.com/ros/ros_comm/issue...

sd1074 gravatar image sd1074  ( 2016-10-29 19:44:22 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2016-10-30 03:50:03 -0500

DavidN gravatar image

According to this implementation https://github.com/ros/ros_comm/blob/... , there are 2 things to note:

  1. If there is no connection established (meaning no subscriber exists), the sequence number remains 0 as default and no message is sent out
  2. If there is at least 1 connection, the sequence number is increased before any message is published, that is why the sequence number in the first msg is 1 instead of 0.

Anyway, according to this http://answers.ros.org/question/38856... , it is not recommended to use header sequence for your logic.

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2016-10-21 17:31:27 -0500

Seen: 2,008 times

Last updated: Oct 30 '16