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
753 stars 911 forks source link

Remapping private topics of anonymous nodes works differently in rospy and roscpp #2324

Open peci1 opened 1 year ago

peci1 commented 1 year ago

When I launch a node from CLI via rosrun and do not set any name, the nodes with anonymous flag generate a random name.

If I pass a local topic remap (~input:=test), rospy correctly remaps this topic, while roscpp does not.

The problem seems to be in this part of this_node code:

https://github.com/ros/ros_comm/blob/842f0f026924323f605495da0b80493f15f0bdce/clients/roscpp/src/libros/this_node.cpp#L120-L170

It first sets name_ to the init_node() argument, possibly replaces it with __name remap, and then it calls names::init().

However, names::init() calls names::resolve(), which in turn calls this_node::getName():

https://github.com/ros/ros_comm/blob/842f0f026924323f605495da0b80493f15f0bdce/clients/roscpp/src/libros/names.cpp#L167-L170

But the name in this_node is only the non-anonymous one - the anonymizing part is appended only after names::init() finishes.

Minimal code showing the problem is this:

#include <ros/ros.h>

int main(int argc, char** argv)
{
  ros::init(argc, argv, "node", ros::init_options::AnonymousName);

  ros::NodeHandle nh ("~");
  ROS_ERROR("%s", nh.resolveName("test").c_str());
}

run as node ~test:=a to see the problem. Running with node ~test:=a __name:=t works as expected, because explicit name setting disables the anonymous node behavior.

Please note that running the node via roslaunch and name="$(anon node)" would not trigger this issue as it does not actually trigger the anonymous init option of the node (it directly generates a random name which is passed to the node in __name:= remap).

For comparison, here is the Python code that works correctly:

import rospy

rospy.init_node("node", anonymous=True)
rospy.logerr(rospy.names.resolve_name("~test"))

The solution would be calling names::init() once more after the name mangling is finished. Would that be okay?

peci1 commented 1 year ago

Fix provided in #2325.