16 for(std::vector<std::string>::const_iterator it = roots.begin(); it != roots.end(); it++) {
17 ui.paramRootCombo->addItem(it->c_str());
36 std::vector<std::string> ret;
37 for(
int i = 0; i < response[2].
size(); i++) {
38 ret.push_back(response[2][i]);
44 ROS_ERROR(
"Failed to getParamNames from master.");
45 return std::vector<std::string>();
50 std::set<std::string> roots;
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);
62 for(
int i = 0; i < parts.size() - 1; i++) {
63 part = part +
"/" + parts.at(i);
64 roots.insert(qPrintable(part));
68 std::vector<std::string> ret;
69 std::copy(roots.begin(), roots.end(), back_inserter(ret));
ParamRootChooser(QWidget *parent=0)
bool param(const std::string ¶m_name, T ¶m_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
const std::string response