Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

rospy: get_num_connections() does not return 0 when a topic is unsubscribed #526

Closed
lsouchet opened this issue Nov 6, 2014 · 8 comments
Closed
Assignees
Labels

Comments

@lsouchet
Copy link

lsouchet commented Nov 6, 2014

Tested on latest indigo.
When I run a test node that displays the number of subscribers for my node using get_num_connections(), I see that this method returns 0 on startup, raise to 1 when I start a rostopic echo, and does not go back to 0 when the listener is killed.

The cpp equivalent using getNumSubscribers() works fine.

To reproduce:
Here is the node code.

import rospy
from std_msgs.msg import String

def talker():
    pub = rospy.Publisher('chatter', String, queue_size=10)
    rospy.init_node('talker', anonymous=True)
    r = rospy.Rate(10) # 10hz
    while not rospy.is_shutdown():
        str = "hello world %s"%rospy.get_time()
        rospy.loginfo(str)
        print("subscribers: " , pub.get_num_connections())
        pub.publish(str)
        r.sleep()

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

rostopic echo /chatter
=> The publisher console outputs "subscribers: 1"
Kill the rostopic echo
=> The publisher console outputs "subscribers: 1"

I was hoping to manage the node activity according to the number of subscribers to that node.

@vrabaud
Copy link
Member

vrabaud commented Nov 6, 2014

and by the way, @lsouchet tried in C++ with getNumSubscribers and that works there

@mikeferguson
Copy link
Contributor

Does it work as expected if queue_size=None (the old blocking-publisher code). If so, then this is likely a regression in the new non-blocking code -- not sure how that code eventually determines a connection is lost though.

@lsouchet
Copy link
Author

lsouchet commented Nov 7, 2014

I just tried with queue_size=None and it works indeed.

pub = rospy.Publisher('chatter', String, queue_size=None)

By roughly ebugging the code, it appears that the connection passed to the remove_connection() method is not the same as the one stored in the publisher connection list.
When going through https://github.com/ros/ros_comm/blob/indigo-devel/clients/rospy/src/rospy/topics.py#L342
Your are trying to disconnect:

<rospy.impl.tcpros_pubsub.QueuedConnection object at 0x7f9abeb29650>

While the connection list contains:

<rospy.impl.tcpros_base.TCPROSTransport object at 0x7f9abeb026d0>

I hope it can help.

@dirk-thomas
Copy link
Member

The problem is that the connection is not removed on the publisher side because of the following check to fail when using the QueuedConnection:

if c in connections:

This is a regression of #308. Any fix will need to be backported to Hydro.

@dirk-thomas
Copy link
Member

Please try the patch from #531 and confirm that it fixes the problem for you, too.

@Karsten1987
Copy link
Contributor

+1, works for me with the given example of @lsouchet

@lsouchet
Copy link
Author

I confirm, this seems to fix my issue!

mjyc pushed a commit to mjyc/ros_comm that referenced this issue Dec 10, 2014
* upstream/indigo-devel:
  fix regression of PR ros#515
  Adding support for fixed-width floating-point and integer array values as per issue ros#400
  Fix exception at roslaunch startup if python is build without ipv6 support.
  Fix exception at roscore startup if python has ipv6 disabled.
  use fileno comparison only as an alternative and when available
  fix removal of QueuedConnection leading to wrong subscriber count (fix ros#526)
  fix comment (fix ros#529)
  unregister statistics publisher
  Fix: TCPROS header validation crash when `callerid` header is not set
  avoid storing subscriber reference in SubscriberStatisticsLogger
  only create SubscriberStatisticsLogger when enabled
  make param functions thread-safe
  Do not use Python when building for Android
  Do not use ifaddrs on Android as it is not natively supported
rsinnet pushed a commit to MisoRobotics/ros_comm that referenced this issue Jun 19, 2017
* upstream/indigo-devel:
  fix regression of PR ros#515
  Adding support for fixed-width floating-point and integer array values as per issue ros#400
  Fix exception at roslaunch startup if python is build without ipv6 support.
  Fix exception at roscore startup if python has ipv6 disabled.
  use fileno comparison only as an alternative and when available
  fix removal of QueuedConnection leading to wrong subscriber count (fix ros#526)
  fix comment (fix ros#529)
  unregister statistics publisher
  Fix: TCPROS header validation crash when `callerid` header is not set
  avoid storing subscriber reference in SubscriberStatisticsLogger
  only create SubscriberStatisticsLogger when enabled
  make param functions thread-safe
  Do not use Python when building for Android
  Do not use ifaddrs on Android as it is not natively supported
@zenified
Copy link

zenified commented Aug 2, 2021

Hi, I have experienced the same issue on melodic, was the fix not propagated?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

No branches or pull requests

6 participants