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

Setting parameters in a launch file does not appear to be working

asked 2012-09-04 11:37:20 -0600

cduguet gravatar image

updated 2012-09-05 07:33:05 -0600

jbohren gravatar image

Hello,

Some script which was working before, now does not work anymore. The issue is that the param instruction in the launch file, does not seem to have any effect in the executable file

<param name="camera_topic" value="/camera/image_rect"  type="str"/>

in my C++ executable, I looked for this "camera_topic" relative parameter as:

ros::param::get("camera_topic",camera_topic);

but I cannot get them easily. setting the same parameter in the program before getting it works, so I conclude it must be something about the launch file. The funny thing is that it worked before (+2 months).

edit retag flag offensive close merge delete

Comments

I'm sure it still works in principle. You can check if and where it is set by rosparam list. If that doesn't help you need to come up with a complete minimal example.

dornhege gravatar image dornhege  ( 2012-09-04 22:05:59 -0600 )edit

I have tried it thanks! I is there indeed. But the node executable somehow still does not read it. Could it be about time delay?

cduguet gravatar image cduguet  ( 2012-09-05 04:47:14 -0600 )edit

Not if set by roslaunch. Test by launching the node manually, when the param is set - I suspect it won't work either.

dornhege gravatar image dornhege  ( 2012-09-05 05:30:28 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
9

answered 2012-09-05 07:30:18 -0600

jbohren gravatar image

If you don't use a forward slash, "ros::param::get" gets a parameter from the node's namespace, but not its private namespace. If you put that parameter tag inside of a <node> tag, it will be in this private namespace.

For example, the following roslaunch xml:

<param name="camera_topic_root" value="/camera/image_rect">
<group ns="group_ns">
    <param name="camera_topic_ns" value="/camera/image_rect">
    <node name="node_name" pkg="foo" type="bar" >
        <param name="camera_topic_private" value="/camera/image_rect">
    </node>
</group>

Would set the parameters:

/camera_topic_root
/group_ns/camera_topic_ns
/group_ns/node_name/camera_topic_private

To get these parameters with the ros::param::get API, you could do each of the following:

ros::param::get("/camera_topic_root",camera_topic);    // /camera_topic_root
ros::param::get("camera_topic_ns",camera_topic);       // /group_ns/camera_topic_ns
ros::param::get("~camera_topic_private",camera_topic); // /group_ns/node_name/camera_topic_private

This is documented slightly less succinctly here.

edit flag offensive delete link more

Comments

Thank you! I missed the "~" in the private parameter! :). Basic question, I hope this answer will help everyone making the same little mistake.

cduguet gravatar image cduguet  ( 2012-09-11 05:28:52 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2012-09-04 11:37:20 -0600

Seen: 8,220 times

Last updated: Sep 11 '12