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

Getting hierarchy level of yaml parameter

asked 2014-08-07 05:18:35 -0500

Tobias Neumann gravatar image

updated 2017-07-11 09:18:23 -0500

lucasw gravatar image

Hi,

I want to use ros param to traverse files like this:

pcl_filter:
  filter:
    filter_cascade_1: 
      in:  cloud_in
      out: cloud_out
      filter:
        first_applied_filter:
          - config_for_filter_1
          - config_for_filter_2
        second_applied_filter:
          - config_for_filter_1
          - config_for_filter_2
    filter_cascade_2:
      in:  other_cloud_in
      out: other_cloud_out
      filter:
        first_applied_filter:
          - config_for_filter_1
          - config_for_filter_2
        second_applied_filter:
          - config_for_filter_1
          - config_for_filter_2

There I would like to get all cascades of the param "filter". In the node pcl_filter I search for something like

std::vector<std::string> param;
getParam("filter", param);

But this just seems to work with something like:

pcl_filter:
  filter:
    - filter_cascade_1
    - filter_cascade_1

And:

std::map<std::string, std::string> param;
getParam("filter", param);

just workes with:

pcl_filter:
  filter:
    filter_cascade_1: a
    filter_cascade_1: b

Does somebody know a way to get all of these parameter?

Thanks for your help

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
8

answered 2014-08-07 08:07:16 -0500

Chrissi gravatar image

updated 2014-08-07 08:32:38 -0500

I just did this for one of my packages. Here is some example code:

#include <XmlRpcValue.h>
...

void my_node::parseParams(ros::NodeHandle n) {
  XmlRpc::XmlRpcValue filters;
  n.getParam("filter", filters);
  ROS_ASSERT(filters.getType() == XmlRpc::XmlRpcValue::TypeStruct);
  for(XmlRpc::XmlRpcValue::ValueStruct::const_iterator it = filters.begin(); it != filters.end(); ++it) {
    ROS_INFO_STREAM("Found filter: " << (std::string)(it->first) << " ==> " << filters[it->first]);
    // Do stuff with filters:
    ROS_INFO_STREAM("filter_cascade_1: in: " << filters[it->first]["in"]);
    ROS_INFO_STREAM("filter_cascade_1: filter: first_applied_filter: config_for_filter_1: " << filters[it->first]["filter"]["first_applied_filter"][0]);
  }
}

This works with xmlrpc structs which is what you get when you query arbitrary parameter namespaces. The iterator contains as it->first the keys of all the parameters found in the filter namespace: filter_cascade_1 and filter_cascade_2 and the it->second contains a xmlrpc struct of the parameters in that namespace. It is not really nice or convenient to use but I hope the example helps a bit.

Edit: Just to elaborate a bit more, the XmlRpcValue::TypeStruct is just a std::map<std::string,XmlRpcValue::TypeStruct>. If you look at the output of this line ROS_INFO_STREAM("Found filter: " << (std::string)(it->first) << " ==> " << filters[it->first]); it should be quite clear how to use it I hope. Took me a few hours to find the right way of doing this so if you have any problems, just let me know.

edit flag offensive delete link more

Comments

Thank you very much, this is what I needed :) Unfortunately there is no ´std::map<std::string,xmlrpcvalue::typestruct>´, that would produce much better code to read, but your solution works just as intended

Tobias Neumann gravatar image Tobias Neumann  ( 2014-08-07 09:08:28 -0500 )edit

You're welcome. I know it's a bit messy... The python interface for this is much better I have to admit but sometimes you just can't avoid using some C++ as well :(

Chrissi gravatar image Chrissi  ( 2014-08-07 09:12:14 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2014-08-07 05:18:35 -0500

Seen: 2,422 times

Last updated: Jul 11 '17