param_edit.cpp
Go to the documentation of this file.
3 #include <QMessageBox>
4 #include "param_root_chooser.h"
5 
7 
8 namespace rqt_paramedit
9 {
10 
11 ParamEdit::ParamEdit() : _treeView(NULL), _model(NULL), _delegate(NULL)
12 {
13  setObjectName("ParamEdit");
14 }
15 
17 {
18  _treeView = new QTreeView();
19  context.addWidget(_treeView);
20 
21  _paramRoot = "/";
22 
24  _treeView->setItemDelegate(_delegate);
25 
26  reload();
27 }
28 
30 {
32  ROS_ERROR("Could not get parameters at: \"%s\"", _paramRoot.c_str());
33  QMessageBox::critical(_treeView, "Error loading parameters",
34  QString("Could not get parameters at: \"%1\"").arg(_paramRoot.c_str()));
35 
36  return;
38  ROS_ERROR("Requested parameter at \"%s\" has non-struct type. Only structs are supported, not single parameters.", _paramRoot.c_str());
39  QMessageBox::critical(_treeView, "Error loading parameters",
40  QString("Requested parameter at \"%1\" has non-struct type. Only structs are supported, not single parameters.\nMaybe, you want to choose the parent containing the selected parameter.").arg(_paramRoot.c_str()));
41 
42  // we have now loaded a parameter that can't be interpreted by the model.
43  // Try to fix that inconsistency somehow by loading from '/' until the user clears this up
44  _paramRoot = "/";
46  }
47 
48  delete _model;
50  _treeView->setModel(_model);
51 }
52 
54 {
55 }
56 
57 void ParamEdit::saveSettings(qt_gui_cpp::Settings& global_settings, qt_gui_cpp::Settings& perspective_settings) const
58 {
59  perspective_settings.setValue("param_root", _paramRoot.c_str());
60 }
61 
62 void ParamEdit::restoreSettings(const qt_gui_cpp::Settings& global_settings, const qt_gui_cpp::Settings& perspective_settings)
63 {
64  _paramRoot = qPrintable(perspective_settings.value("param_root", "/").toString());
65  reload();
66 }
67 
69 {
70  ParamRootChooser dialog;
71  if(dialog.exec() == QDialog::Accepted) {
72  if(dialog.selectedParamRoot().empty()) {
73  ROS_ERROR("ParamRootChooser Accepted, but no valid parameter chosen.");
74  } else {
75  _paramRoot = dialog.selectedParamRoot();
76  reload();
77  }
78  }
79 }
80 
81 }
82 
#define NULL
XmlRpc::XmlRpcValue _xmlrpc
Definition: param_edit.h:49
virtual void initPlugin(qt_gui_cpp::PluginContext &context)
Definition: param_edit.cpp:16
virtual void restoreSettings(const qt_gui_cpp::Settings &global_settings, const qt_gui_cpp::Settings &perspective_settings)
Definition: param_edit.cpp:62
XmlRpcItemDelegate * _delegate
Definition: param_edit.h:52
void addWidget(QWidget *widget)
XmlRpcModel * _model
Definition: param_edit.h:51
Type const & getType() const
bool getParam(const std::string &key, std::string &s) const
std::string selectedParamRoot() const
void setValue(const QString &key, const QVariant &value)
virtual void triggerConfiguration()
Definition: param_edit.cpp:68
std::string _paramRoot
Definition: param_edit.h:48
virtual void saveSettings(qt_gui_cpp::Settings &global_settings, qt_gui_cpp::Settings &perspective_settings) const
Definition: param_edit.cpp:57
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
ros::NodeHandle _nh
Definition: param_edit.h:47
virtual void shutdownPlugin()
Definition: param_edit.cpp:53
QVariant value(const QString &key, const QVariant &defaultValue=QVariant()) const


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