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

Passing an array of arrays of doubles from a yaml config file

asked 2021-02-03 08:04:18 -0500

mamado gravatar image

I am using ROS2 foxy and I have an array of arrays of doubles that should set one of the variables in the node. Is it possible to pass that from the yaml config file to c++? I tried to wrap it in a std::vector<std::vector<double>> but I get an error.

My yaml file looks like this:

offboard_navigator:
  ros__parameters:
    setpoints_lla: [[47.3977507,  8.5456073,  5],
        [47.39774376, 8.54576301, 6],
        [47.39781572, 8.54577784, 5],
        [47.39781739, 8.54558749, 6],
        [47.3977507,  8.5456073,  0]]

And this is how I declare the parameter in the ROS2 node code:

    this->declare_parameter< std::vector< std::vector <double> > >("setpoints_lla", {{0.0,0.0,0.0}});
    this->get_parameter("setpoints_lla", setpoints_list_param_);

And this is the error I am getting:

/opt/ros/foxy/include/rclcpp/node_impl.hpp:166:15: error: no matching function for call to ‘rclcpp::ParameterValue::ParameterValue(const std::vector<std::vector<double, std::allocator<double> > >&)’
  166 |       rclcpp::ParameterValue(default_value)

Is there another way to implement this so that I can set one of my variables using an array of arrays. Note: all my inner arrays have the same size.

,

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
0

answered 2021-06-29 18:53:59 -0500

404RobotNotFound gravatar image

According to the design document for params, a 2D array of any type is not supported.

However, if you want to have a 2D array, instead of adding a parser yourself you can use the yaml-cpp library to do a lot of the heavy lifting. You would still pass in a string, but then just call YAML::Node yaml_node = YAML::Load(string) and it will parse it, and you can use its interface to get the values. Here is the yaml-cpp tutorial

edit flag offensive delete link more
0

answered 2021-06-27 21:40:49 -0500

hosh gravatar image

No it's not possible to pass a vector 2D directly as a ros2 parameter. You have to define the parameter as a string: setpoints_lla: "[[47.3977507, 8.5456073, 5], [47.39774376, 8.54576301, 6], [47.39781572, 8.54577784, 5], [47.39781739, 8.54558749, 6], [47.3977507, 8.5456073, 0]]"

Then you can pass this to a parser like this (cite to the navigation stack ):

  std::vector<std::vector<float>> parseVVF(const std::string & input, std::string & error_return)
  {
    std::vector<std::vector<float>> result;

    std::stringstream input_ss(input);
    int depth = 0;
    std::vector<float> current_vector;
    while (!!input_ss && !input_ss.eof()) {
      switch (input_ss.peek()) {
      case EOF:
        break;
      case '[':
        depth++;
        if (depth > 2) {
          error_return = "Array depth greater than 2";
          return result;
        }
        input_ss.get();
        current_vector.clear();
        break;
      case ']':
        depth--;
        if (depth < 0) {
          error_return = "More close ] than open [";
          return result;
        }
        input_ss.get();
        if (depth == 1) {
          result.push_back(current_vector);
        }
        break;
      case ',':
      case ' ':
      case '\t':
        input_ss.get();
        break;
      default:  // All other characters should be part of the numbers.
        if (depth != 2) {
          std::stringstream err_ss;
          err_ss << "Numbers at depth other than 2. Char was '" << char(input_ss.peek()) << "'.";
          error_return = err_ss.str();
          return result;
        }
        float value;
        input_ss >> value;
        if (!!input_ss) {
          current_vector.push_back(value);
        }
        break;
      }
    }
    if (depth != 0) {
      error_return = "Unterminated vector string.";
    } else {
      error_return = "";
    }
    return result;
  }
edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2021-02-03 08:04:18 -0500

Seen: 3,967 times

Last updated: Jun 29 '21