Go to the documentation of this file.00001 #include "rosgui_paramedit/param_edit.h"
00002 #include <pluginlib/class_list_macros.h>
00003 #include <QMessageBox>
00004 #include "param_root_chooser.h"
00005
00006 PLUGINLIB_DECLARE_CLASS(rosgui_paramedit, ParamEdit, rosgui_paramedit::ParamEdit, rqt_gui_cpp::Plugin)
00007
00008 namespace rosgui_paramedit
00009 {
00010
00011 ParamEdit::ParamEdit() : _treeView(NULL), _model(NULL), _delegate(NULL)
00012 {
00013 setObjectName("ParamEdit");
00014 }
00015
00016 void ParamEdit::initPlugin(qt_gui_cpp::PluginContext& context)
00017 {
00018 _treeView = new QTreeView();
00019 context.addWidget(_treeView);
00020
00021 _paramRoot = "/";
00022
00023 _delegate = new XmlRpcItemDelegate(_treeView);
00024 _treeView->setItemDelegate(_delegate);
00025
00026 reload();
00027 }
00028
00029 void ParamEdit::reload()
00030 {
00031 if(!_nh.getParam(_paramRoot, _xmlrpc)) {
00032 ROS_ERROR("Could not get parameters at: \"%s\"", _paramRoot.c_str());
00033 QMessageBox::critical(_treeView, "Error loading parameters",
00034 QString("Could not get parameters at: \"%1\"").arg(_paramRoot.c_str()));
00035
00036 return;
00037 } else if(_xmlrpc.getType() != XmlRpc::XmlRpcValue::TypeStruct) {
00038 ROS_ERROR("Requested parameter at \"%s\" has non-struct type. Only structs are supported, not single parameters.", _paramRoot.c_str());
00039 QMessageBox::critical(_treeView, "Error loading parameters",
00040 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()));
00041
00042
00043
00044 _paramRoot = "/";
00045 _nh.getParam(_paramRoot, _xmlrpc);
00046 }
00047
00048 delete _model;
00049 _model = new XmlRpcModel(&_xmlrpc, _paramRoot, &_nh);
00050 _treeView->setModel(_model);
00051 }
00052
00053 void ParamEdit::shutdownPlugin()
00054 {
00055 }
00056
00057 void ParamEdit::saveSettings(qt_gui_cpp::Settings& global_settings, qt_gui_cpp::Settings& perspective_settings) const
00058 {
00059 perspective_settings.setValue("param_root", _paramRoot.c_str());
00060 }
00061
00062 void ParamEdit::restoreSettings(const qt_gui_cpp::Settings& global_settings, const qt_gui_cpp::Settings& perspective_settings)
00063 {
00064 _paramRoot = qPrintable(perspective_settings.value("param_root", "/").toString());
00065 reload();
00066 }
00067
00068 void ParamEdit::triggerConfiguration()
00069 {
00070 ParamRootChooser dialog;
00071 if(dialog.exec() == QDialog::Accepted) {
00072 if(dialog.selectedParamRoot().empty()) {
00073 ROS_ERROR("ParamRootChooser Accepted, but no valid parameter chosen.");
00074 } else {
00075 _paramRoot = dialog.selectedParamRoot();
00076 reload();
00077 }
00078 }
00079 }
00080
00081 }
00082