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

Setting parameters just work through rqt_reconfigure, not rosparam

asked 2020-03-31 09:04:48 -0500

cheesee61 gravatar image

Hello ROS developers,

I am currently using this depthimage_to_laserscan package. I wanted to change some parameters (for instance range_min). When I do it in rqt_reconfigure, everything is fine: the parameter changes, I can see it in rviz. But when I do it with rosparam set, rosparam get verifies that it is set, but neither the value changes in rviz nor in rqt_reconfigure. So why can I change the parameter just through rqt_reconfigure and not the command-line tool rosparam?

I am using Ubuntu 16.04 LTS with ROS kinetic.

I would appreciate every help, thanks in advance guys!

Best regards cheesee61

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2020-03-31 10:12:31 -0500

gvdhoorn gravatar image

updated 2020-03-31 10:46:54 -0500

When I do it in rqt_reconfigure, everything is fine: the parameter changes, I can see it in rviz. But when I do it with rosparam set, rosparam get verifies that it is set, but neither the value changes in rviz nor in rqt_reconfigure.

This is expected. See below.

So why can I change the parameter just through rqt_reconfigure and not the command-line tool rosparam?

Because you should (and node authors should, and typically do) consider the rosparam uploaded parameters as akin to file-based configurations. With this I mean: those are typically read once, at startup of the program (nodes, in this case).

Just as with other programs, you could change values in the configuration file, but your running program would not notice anything has changed, as it's not paying attention to the configuration file any more after it has been started. ROS nodes are essentially just ordinary programs, so they don't notice these changes either.

But it would certainly be convenient if we could make running programs take a look at changed values in their configuration files. With Linux daemons (programs running in the background, somewhat similar to Windows services) and even regular programs, this is typically done by sending the program a SIGHUP signal (wikipedia, Windows and OSX have similar mechanisms). This tells the program to reload its configuration, as if it were shutdown and restarted.

For ROS nodes, we don't use SIGHUP (although we could), but there is a special interface called dynamic_reconfigure which does the same thing (rqt_reconfigure is just a graphical user interface on-top of dynamic_reconfigure). In fact, it does a little more, as besides telling the node something has changed in its configuration, it also tells the node what has changed, and what the new values are.

Summarising: rosparam set changes the configuration of a node, but doesn't tell the node anything has changed. As nodes are not supposed to reload their configuration periodically (this is wasteful of resources), they don't realise something has changed and "nothing happens". With dynamic_reconfigure we do tell the node its configuration has changed, so it reads the updates and accordingly, you'll see the changes in behaviour (or visualisation).

And finally: the title of your question:

Setting parameters just work through rqt_reconfigure, not rosparam

is not actually correct. Updating the parameters using rosparam set most likely works fine (you mention this yourself: you've used rosparam get to verify it). What doesn't happen is the nodes re-reading their parameters. But that is actually expected -- and recommended -- behaviour.

edit flag offensive delete link more

Comments

Technically, nodes reloading their configuration periodically is called polling. For data which infrequently changes (such as configuration data), this is rather wasteful, as most of the times a node will be re-reading the exact same data.

Using dynamic_reconfigure makes everything event-based. This is efficient in this case, as the node will only act whenever there is something to actually act upon.

In a distributed system with potentially hundreds of nodes, only doing work when there is work is highly desirable.

gvdhoorn gravatar image gvdhoorn  ( 2020-03-31 10:14:49 -0500 )edit

One could ask: but can't I just add ros::param::get(..) in my callback or while-loop? And the answer would be: certainly. However, as mentioned above, that would essentially be polling, which is rather wasteful.

Doubly so in this case, as ros::param::get(..) is somewhat similar to a service call, so you incur quite some overhead reading a single parameter (there is a cached version of ros::param::get(..), which sort of combines notifications of parameter changes with polling, but it doesn't come with any of the niceties of dynamic_reconfigure, so I typically don't use it).

gvdhoorn gravatar image gvdhoorn  ( 2020-03-31 10:20:43 -0500 )edit

Awesome explanations mate, thank you very much!

cheesee61 gravatar image cheesee61  ( 2020-03-31 11:07:48 -0500 )edit

Thanks so much for explaining the "rosparam set" and "dynamic_reconfigure", so easy to understand and useful.

Enjoy_Robotics gravatar image Enjoy_Robotics  ( 2020-06-27 04:28:23 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-03-31 09:04:48 -0500

Seen: 1,215 times

Last updated: Mar 31 '20