MainWindow.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2015, C. Dornhege, University of Freiburg
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright notice,
11  * this list of conditions and the following disclaimer in the documentation
12  * and/or other materials provided with the distribution.
13  * * Neither the name of the University of Freiburg nor the names
14  * of its contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
21  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
23  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
24  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
25  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
26  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27  */
28 
29 #include "MainWindow.h"
30 #include <stdio.h>
31 #include "settingsDialog.h"
32 
33 MainWindow::MainWindow(XmlRpc::XmlRpcValue & initParams, const std::string & paramRoot, ros::NodeHandle* nh)
34  : _xmlrpc(initParams), _paramRoot(paramRoot), _nh(nh)
35 {
36  setupUi(this);
37 
40 
41  _delegate = new XmlRpcItemDelegate(treeView);
42  treeView->setItemDelegate(_delegate);
43 
44  actionReload->setIcon(QIcon::fromTheme("view-refresh"));
45 }
46 
47 void MainWindow::setModel(QAbstractItemModel * model)
48 {
49  treeView->setModel(model);
50  treeView->resizeColumnToContents(0);
51 }
52 
54 {
55  if(!_nh->getParam(_paramRoot, _xmlrpc)) {
56  ROS_ERROR("Could not get parameters at: \"%s\"", _paramRoot.c_str());
57  return;
58  }
59 
60  unsigned int maxDisplayLength = 120;
61  if(_model)
62  maxDisplayLength = _model->getMaxDisplayLength();
63 
64  delete _model;
66 
67  _model->setMaxDisplayLength(maxDisplayLength);
68 
70  ROS_INFO("Reloaded parameters from \"%s\"", _paramRoot.c_str());
71 }
72 
74 {
75  SettingsDialog dialog(this);
77  if(_model)
79 
80  if(dialog.exec()) {
82  if(_model) {
84  }
85  }
86 }
87 
XmlRpc::XmlRpcValue _xmlrpc
Definition: MainWindow.h:49
std::string _paramRoot
Definition: MainWindow.h:50
unsigned int getDoubleDecimals() const
XmlRpcItemDelegate * _delegate
Definition: MainWindow.h:53
void setDoubleDecimals(unsigned int decs)
MainWindow(XmlRpc::XmlRpcValue &initParams, const std::string &paramRoot, ros::NodeHandle *nh)
Definition: MainWindow.cpp:33
unsigned int getDoubleDecimals() const
void setDoubleDecimals(unsigned int decs)
void setMaxDisplayLength(unsigned int l)
Definition: xmlRpcModel.h:65
void setMaxDisplayLength(unsigned int l)
#define ROS_INFO(...)
bool getParam(const std::string &key, std::string &s) const
XmlRpcModel * _model
Definition: MainWindow.h:55
void on_actionReload_triggered()
Definition: MainWindow.cpp:53
QAbstractItemModel for XmlRpcValues.
Definition: xmlRpcModel.h:43
void setModel(QAbstractItemModel *model)
Definition: MainWindow.cpp:47
ros::NodeHandle * _nh
Definition: MainWindow.h:51
int getMaxDisplayLength() const
#define ROS_ERROR(...)
void on_actionSettings_triggered()
Definition: MainWindow.cpp:73
unsigned int getMaxDisplayLength() const
Definition: xmlRpcModel.h:64


qt_paramedit
Author(s): Christian Dornhege
autogenerated on Mon Feb 28 2022 23:37:51