ros / ros_comm

ROS communications-related packages, including core client libraries (roscpp, rospy, roslisp) and graph introspection tools (rostopic, rosnode, rosservice, rosparam).
http://wiki.ros.org/ros_comm
752 stars 911 forks source link

Remap cycle in rospy and inconsistent names between publisher and its implementation #2175

Open tpet opened 3 years ago

tpet commented 3 years ago

Remapping is done twice - in publisher and its internal implementation which leads to possible cycles and the publisher and its internal implementation reporting different topic names. In some cases remapping just does not work.

(I edited the issue to simplify it.)

One of failure cases is switching topics: you can't remap a to b and b to a in the same node. The cycle may appear with resolved names.

Example with rospy_remap_cycle node

#!/usr/bin/env python
import rospy
from std_msgs.msg import Empty
rospy.init_node('rospy_remap_cycle')

pub = rospy.Publisher('published', Empty, queue_size=1)
sub = rospy.Subscriber('subscribed', Empty, lambda msg: None, queue_size=1)

for name, obj in [('pub', pub), ('pub.impl', pub.impl), ('sub', sub), ('sub.impl', sub.impl)]:
    print('%-8s name: %s, resolved: %s' % (name, obj.name, obj.resolved_name))

rospy.spin()

launched from commandline:

source /opt/ros/noetic/setup.bash
roscore &
./rospy_remap_cycle published:=subscribed subscribed:=published
pub      name: /subscribed, resolved: /subscribed
pub.impl name: /published, resolved: /published
sub      name: /published, resolved: /published
sub.impl name: /subscribed, resolved: /subscribed

With cycle appearing with resolved names:

./rospy_remap_cycle __ns:=private published:=/private/subscribed subscribed:=/private/published
pub      name: /private/subscribed, resolved: /private/subscribed
pub.impl name: /private/published, resolved: /private/published
sub      name: /private/published, resolved: /private/published
sub.impl name: /private/subscribed, resolved: /private/subscribed

Note that the publisher/subscriber reports expected topic names but not so the internal implementations.

peci1 commented 9 months ago

Workaround for nodes you can edit: put the following snippet before you start creating publishers and subscribers:

orig_init = rospy.topics._TopicImpl.__init__
def new_init(self, name, dataclass):
    orig_init(self, name, dataclass)
    self.name = self.resolved_name = name
rospy.topics._TopicImpl.__init__ = new_init