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

How to remap a private parameter

asked 2018-02-21 02:45:27 -0600

Felix Widmaier gravatar image

In a launch file I want to remap parameters of my node to other, already existing parameters. It is working for global parameters but not for private ones.

This is a simple example node "param.py":

#!/usr/bin/env python
"""Just testing parameter mapping."""
import rospy

rospy.init_node("param")
print(rospy.get_param("foo"))
print(rospy.get_param("bar"))
print(rospy.get_param("~baz"))

The node is launched by this launch file "param.launch":

<launch>
    <node name="param" pkg="mypkg" type="param.py" output="screen">
        <remap from="/bar" to="/foo" />
        <remap from="baz" to="foo" />
    </node>
</launch>

In a terminal I run:

rosparam set foo 42
roslaunch mypkg param.launch

The output is:

42
42
KeyError: '~baz'

How can I make it work?

edit retag flag offensive close merge delete

Comments

I'm afraid rosparam would fail without Parameter server running. Maybe add roscore command a line above?

130s gravatar image 130s  ( 2018-09-20 12:47:55 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2018-02-21 02:47:04 -0600

Felix Widmaier gravatar image

Private parameter names have to be prefixed with ~ even when the <remap> is defined inside the <node> tag:

<launch>
    <node name="param" pkg="mypkg" type="param.py" output="screen">
        <remap from="/bar" to="/foo" />
        <remap from="~baz" to="foo" />
    </node>
</launch>

Output:

42
42
42
edit flag offensive delete link more

Comments

1

Nice dig! Added to remap page.

130s gravatar image 130s  ( 2018-09-20 12:46:53 -0600 )edit

Could it be that this approach does not work for roscpp nodes? The remapping is not applied for NodeHandles created as

ros::NodeHandle private_nh("~"); assert(private_nh.resolveName("baz") == "/param/foo");

with the launch file snippet from this answer.

Or is this not what to expect?

meyerj gravatar image meyerj  ( 2020-02-24 14:53:39 -0600 )edit

Furthermore I think what is meant by "assignment for private node parameters" in the original content of the wiki page is not remapping. Both, rospy and roscpp, support assigning parameters via "special" remappings _key:=value, but that is not the same as remapping parameter name ~key to ~value.

meyerj gravatar image meyerj  ( 2020-02-24 14:56:10 -0600 )edit

Found the problem with the snippet in my first post: The target of the remapping is not private, so private_nh.resolveName("baz") == "/foo", not "/param/foo".

meyerj gravatar image meyerj  ( 2020-02-24 15:05:37 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2018-02-21 02:45:27 -0600

Seen: 8,617 times

Last updated: Feb 21 '18