Note: This tutorial assumes that you have completed the previous tutorials: ROS Tutorials.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Accessing Private Names from a NodeHandle

Description: This tutorial will show you how to access private Names with roscpp's NodeHandle API.

Tutorial Level: BEGINNER

Next Tutorial: Using Class Methods as Callbacks

Why not just ~name?

The introduction of NodeHandles in roscpp created something of a conundrum when dealing with private names. If I create a NodeHandle with its own namespace:

   1 ros::init(argc, argv, "my_node_name");
   2 ros::NodeHandle nh("/my_node_handle_namespace");

Where should a private name resolve? Some options would be:

  • /my_node_handle_namespace/my_node_name/name

  • my_node_name/my_node_handle_namespace/name

  • /my_node_handle_namespace/name

  • Something else entirely

For this reason, NodeHandle does not allow passing private names directly to its methods, or to constructors that take a NodeHandle as an argument.

Accessing Private Names

The solution is to construct a NodeHandle with a private name as its namespace:

   1 ros::init(argc, argv, "my_node_name");
   2 ros::NodeHandle nh1("~");  // must be in main()
   3 ros::NodeHandle nh2("~foo");

nh1's namespace is /my_node_name, and nh2's namespace is /my_node_name/foo.

So instead of doing this:

   1 ros::NodeHandle nh;
   2 nh.getParam("~name", ... );

You do this:

   1 ros::NodeHandle nh("~");
   2 nh.getParam("name", ... );

Next Tutorial: Using Class Methods as Callbacks

Wiki: roscpp_tutorials/Tutorials/AccessingPrivateNamesWithNodeHandle (last edited 2018-05-08 08:07:56 by AndreaPonza)