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

How to read a vector<strings> parameter from command line

asked 2014-10-09 07:30:16 -0600

Markus Bader gravatar image

updated 2014-10-09 07:34:51 -0600

Hi

I have a std::vector<std::string> parameter and I like to read the values getParam. How does the command line syntax look to read my names param from bash.


e.g. rosrun my_pgk my_node _names:=???????
I tried:
_names:="max susi"
_names:="max, susi"
_names:="[max, susi]"
_names:="(max, susi)"
nothing worked :-(


My code looks like this:

std::vector<std::string> names;
n_param_.getParam ( "names", names);

//For debugging
std::stringstream ss;
for ( size_t i = 0; i < names.size(); i++ ) ss << ( i!=0?", ":"" ) << names[i];
ROS_INFO ( "names: %s", ss.str().c_str() );

Greetings Markus

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
2

answered 2014-10-10 06:50:38 -0600

Markus Bader gravatar image

updated 2014-10-10 06:51:43 -0600

For the moment I solved the problem with a hack

std::string tmp;
std::vector<std::string> names;
n_param_.getParam ( "names", tmp);
boost::erase_all(tmp, " ");
boost::split ( names, tmp, boost::is_any_of(","));

now I can read it with _names:="max, susi"

edit flag offensive delete link more

Comments

For Indigo and newer, please refer to @peci1's answer below.

gvdhoorn gravatar image gvdhoorn  ( 2018-01-28 03:14:48 -0600 )edit
7

answered 2018-01-25 08:45:21 -0600

peci1 gravatar image

Now on ROS Indigo, I can get the list to an argument as follows:

rosrun pkg node _param:="[1, 2]"

This will put a list with two numbers on the param server.

It seems to be documented here: http://wiki.ros.org/ROS/YAMLCommandLine . Strings would be quoted by the other type of quotes than the one used to quote the whole list.

In rospy, it works out of the box:

print rospy.get_param("~param")[0]

In roscpp, the use is also as easy as:

std::vector<double> v;
pnh.param("param", v, std::vector<double>());

Problems can arise when you want to pass the array to the node using a roslaunch file - then the clasical "<arg> and <param> policy" won't work, since roslaunch doesn't know about list types and will convert the list to a single string. Since Lunar, you may use the construct <param name="param" type="yaml" value="$(arg param)" /> (documentation). In Indigo, you can achieve a similar result by <rosparam param="param" subst_value="True">$(arg param)</rosparam> (documentation).

edit flag offensive delete link more

Comments

<arg name="string_list" default="[this, is, list]"/><rosparam param="string_list" subst_value="True">$(arg string_list)</rosparam>

This shows the following error: requires the 'string_list' arg to be set

2ROS0 gravatar image 2ROS0  ( 2018-01-28 17:45:51 -0600 )edit

@2ROS0 Which ROS version? Did you try enclosing each of the three strings in single quotes?

peci1 gravatar image peci1  ( 2018-01-28 18:09:39 -0600 )edit

kinetic, I defaulted to the hack in @Markus Bader answer. I think I did try with the quotes but I'll try again in a bit and edit this comment

2ROS0 gravatar image 2ROS0  ( 2018-01-28 18:11:47 -0600 )edit

yeah I tried with the whitelist example on the documentation you linked as is without any changes. It gives the same answer even though those are ints and not strings

2ROS0 gravatar image 2ROS0  ( 2018-01-28 18:16:31 -0600 )edit

@2ROS0 So does it work for you in the end?

peci1 gravatar image peci1  ( 2018-01-29 07:07:52 -0600 )edit

No, it seems there is a bug somewhere. I removed everything else from my launchfile and tried with a simple image_view node as shown below but still same error. Is there someone that can check to see if the same error occurs to them? I am running ROS Kinetic

2ROS0 gravatar image 2ROS0  ( 2018-01-29 10:41:20 -0600 )edit
1

Here is my basic launchfile:

<launch>

<node pkg="image_view" name="image_view" type="image_view" output="screen">

   <arg name="whitelist" default="[3, 2]"/>

   <rosparam param="whitelist" subst_value="True">$(arg whitelist)</rosparam>

</node>

</launch>

2ROS0 gravatar image 2ROS0  ( 2018-01-29 10:41:58 -0600 )edit
1

@2ROS0 The <arg> tag has to be a direct child of the <launch> element, and not inside the <node>. Then it will work.

peci1 gravatar image peci1  ( 2018-01-29 10:44:35 -0600 )edit
0

answered 2014-10-09 15:07:56 -0600

Wolf gravatar image

updated 2014-10-10 01:24:40 -0600

1) Your code should work in groovy and above. If you used fuerte or previous versions you'd need to change:

std::vector<std::string> names;

for

XmlRpc::XmlRpcValue names;

XmlRpc value can conditionally contain primitive data values, structures or arrays. If param names is an array it will return an array into the XmlRpcValue type object and the rest of your code will work without modifications...

2) I am not sure if it is possible to set parameter array via command line node argument at all. It is possibile programmatically or using command line rosparam set. If you used rosparam set names it'd be [max, susi]. However, this apparently does not work as rosrun node argument. Maybe the command line parsing is not able to cope with that.

edit flag offensive delete link more

Comments

Since Groovy, it is actually possible to retrieve lists and maps the way the OP describes. See Parameter Server/Retrieving Lists.

gvdhoorn gravatar image gvdhoorn  ( 2014-10-10 00:59:25 -0600 )edit

I edited the answer accordingly. Thanks for the update!

Wolf gravatar image Wolf  ( 2014-10-10 01:24:18 -0600 )edit
1

@gvdhoorn The Parameter Server/Retrieving Lists is not listing a clear solution.

Markus Bader gravatar image Markus Bader  ( 2014-10-10 06:47:25 -0600 )edit

@Markus Bader: my comment wasn't meant as one. I simply wanted to draw @Wolf 's attention to the fact that since Groovy we can actually retrieve maps and lists directly from the parameter server. Without having to use the XmlRpc::XmlRpcValue work around.

gvdhoorn gravatar image gvdhoorn  ( 2014-10-10 07:05:15 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2014-10-09 07:30:16 -0600

Seen: 7,394 times

Last updated: Jan 25 '18