param_root_chooser.cpp
Go to the documentation of this file.
00001 #include "param_root_chooser.h"
00002 #include <ros/ros.h>
00003 #include <ros/master.h>
00004 #include <algorithm>
00005 #include <iterator>
00006 #include <set>
00007 
00008 ParamRootChooser::ParamRootChooser(QWidget* parent) : QDialog(parent)
00009 {
00010     ui.setupUi(this);
00011 
00012     // change paramRoot from list/combo/tree (to get somehow) and reload
00013     std::vector<std::string> allParams = getParamNamesFromMaster();
00014     std::vector<std::string> roots = getParameterRoots(allParams);
00015 
00016     for(std::vector<std::string>::const_iterator it = roots.begin(); it != roots.end(); it++) {
00017         ui.paramRootCombo->addItem(it->c_str());
00018     }
00019 }
00020 
00021 std::string ParamRootChooser::selectedParamRoot() const
00022 {
00023     return _selectedParam;
00024 }
00025 
00026 void ParamRootChooser::on_paramRootCombo_currentIndexChanged(const QString & text)
00027 {
00028     _selectedParam = qPrintable(text);
00029 }
00030 
00031 std::vector<std::string> ParamRootChooser::getParamNamesFromMaster() const
00032 {
00033     XmlRpc::XmlRpcValue params, response, payload;
00034     params[0] = ros::this_node::getName();
00035     if(ros::master::execute("getParamNames", params, response, payload, true)) {
00036         std::vector<std::string> ret;
00037         for(int i = 0; i < response[2].size(); i++) {
00038             ret.push_back(response[2][i]);
00039         }
00040 
00041         return ret;
00042     } 
00043 
00044     ROS_ERROR("Failed to getParamNames from master.");
00045     return std::vector<std::string>();
00046 }
00047 
00048 std::vector<std::string> ParamRootChooser::getParameterRoots(const std::vector<std::string> paramNames) const
00049 {
00050     std::set<std::string> roots;
00051     roots.insert("/");
00052 
00053     // split each param like: /test/param/a into single parts
00054     // and add each prefix to the param list
00055     // -> /test, /test/param
00056     for(std::vector<std::string>::const_iterator it = paramNames.begin(); it != paramNames.end(); it++) {
00057         QString param = it->c_str();
00058         QStringList parts = param.split("/", QString::SkipEmptyParts);
00059         if(parts.size() < 2)
00060             continue;
00061         QString part = "";
00062         for(int i = 0; i < parts.size() - 1; i++) {
00063             part = part + "/" + parts.at(i);
00064             roots.insert(qPrintable(part));
00065         }
00066     }
00067 
00068     std::vector<std::string> ret;
00069     std::copy(roots.begin(), roots.end(), back_inserter(ret));
00070 
00071     return ret;
00072 }
00073 


rqt_paramedit
Author(s): Christian Dornhege
autogenerated on Thu Jun 6 2019 20:47:44