param_root_chooser.cpp
Go to the documentation of this file.
1 #include "param_root_chooser.h"
2 #include <ros/ros.h>
3 #include <ros/master.h>
4 #include <algorithm>
5 #include <iterator>
6 #include <set>
7 
8 ParamRootChooser::ParamRootChooser(QWidget* parent) : QDialog(parent)
9 {
10  ui.setupUi(this);
11 
12  // change paramRoot from list/combo/tree (to get somehow) and reload
13  std::vector<std::string> allParams = getParamNamesFromMaster();
14  std::vector<std::string> roots = getParameterRoots(allParams);
15 
16  for(std::vector<std::string>::const_iterator it = roots.begin(); it != roots.end(); it++) {
17  ui.paramRootCombo->addItem(it->c_str());
18  }
19 }
20 
22 {
23  return _selectedParam;
24 }
25 
27 {
28  _selectedParam = qPrintable(text);
29 }
30 
31 std::vector<std::string> ParamRootChooser::getParamNamesFromMaster() const
32 {
33  XmlRpc::XmlRpcValue params, response, payload;
34  params[0] = ros::this_node::getName();
35  if(ros::master::execute("getParamNames", params, response, payload, true)) {
36  std::vector<std::string> ret;
37  for(int i = 0; i < response[2].size(); i++) {
38  ret.push_back(response[2][i]);
39  }
40 
41  return ret;
42  }
43 
44  ROS_ERROR("Failed to getParamNames from master.");
45  return std::vector<std::string>();
46 }
47 
48 std::vector<std::string> ParamRootChooser::getParameterRoots(const std::vector<std::string> paramNames) const
49 {
50  std::set<std::string> roots;
51  roots.insert("/");
52 
53  // split each param like: /test/param/a into single parts
54  // and add each prefix to the param list
55  // -> /test, /test/param
56  for(std::vector<std::string>::const_iterator it = paramNames.begin(); it != paramNames.end(); it++) {
57  QString param = it->c_str();
58  QStringList parts = param.split("/", QString::SkipEmptyParts);
59  if(parts.size() < 2)
60  continue;
61  QString part = "";
62  for(int i = 0; i < parts.size() - 1; i++) {
63  part = part + "/" + parts.at(i);
64  roots.insert(qPrintable(part));
65  }
66  }
67 
68  std::vector<std::string> ret;
69  std::copy(roots.begin(), roots.end(), back_inserter(ret));
70 
71  return ret;
72 }
73 
ParamRootChooser(QWidget *parent=0)
bool param(const std::string &param_name, T &param_val, const T &default_val)
std::vector< std::string > getParameterRoots(const std::vector< std::string > paramNames) const
Extracts a list of all possible parameter roots from a list of parameter names.
ROSCPP_DECL const std::string & getName()
std::vector< std::string > getParamNamesFromMaster() const
Retrieves the names of all parameters from master server.
std::string _selectedParam
std::string selectedParamRoot() const
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
void on_paramRootCombo_currentIndexChanged(const QString &text)
Ui::ParamRootChooserDialog ui
#define ROS_ERROR(...)
const std::string response


rqt_paramedit
Author(s): Christian Dornhege
autogenerated on Mon Feb 28 2022 23:37:53