PreferencesDialogROS.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
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  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
30 #include <QDir>
31 #include <QFileInfo>
32 #include <QSettings>
33 #include <QHBoxLayout>
34 #include <QTimer>
35 #include <QLabel>
37 #include <QMessageBox>
38 #include <ros/exceptions.h>
39 #include <rtabmap/utilite/UStl.h>
40 
41 using namespace rtabmap;
42 
43 PreferencesDialogROS::PreferencesDialogROS(const QString & configFile) :
44  configFile_(configFile)
45 {
46 
47 }
48 
50 {
51  QFile::remove(getTmpIniFilePath());
52 }
53 
55 {
56  if(configFile_.isEmpty())
57  {
58  return PreferencesDialog::getIniFilePath();
59  }
60  return configFile_;
61 }
62 
64 {
65  return QDir::homePath()+"/.ros/"+QFileInfo(configFile_).fileName()+".tmp";
66 }
67 
68 void PreferencesDialogROS::readCameraSettings(const QString & filePath)
69 {
70  this->setInputRate(0);
71 }
72 
74 {
75  return tr("Reading parameters from the ROS server...");
76 }
77 
78 bool PreferencesDialogROS::readCoreSettings(const QString & filePath)
79 {
80  QString path = getIniFilePath();
81  if(!filePath.isEmpty())
82  {
83  path = filePath;
84  }
85 
86  ros::NodeHandle nh;
87  ROS_INFO("%s", this->getParamMessage().toStdString().c_str());
88  bool validParameters = true;
89  int readCount = 0;
91  for(rtabmap::ParametersMap::iterator i=parameters.begin(); i!=parameters.end(); ++i)
92  {
93  if(i->first.compare(rtabmap::Parameters::kRtabmapWorkingDirectory()) == 0)
94  {
95  // use working directory of the GUI, not the one on rosparam server
96  QSettings settings(path, QSettings::IniFormat);
97  settings.beginGroup("Core");
98  QString value = settings.value(rtabmap::Parameters::kRtabmapWorkingDirectory().c_str(), "").toString();
99  if(!value.isEmpty() && QDir(value).exists())
100  {
101  this->setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(), value.toStdString());
102  }
103  else
104  {
105  // use default one
106  this->setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(), (QDir::homePath()+"/.ros").toStdString());
107  }
108  settings.endGroup();
109  }
110  else
111  {
112  std::string value;
113  if(nh.getParam(i->first,value))
114  {
115  PreferencesDialog::setParameter(i->first, value);
116  ++readCount;
117  }
118  else
119  {
120  validParameters = false;
121  }
122  }
123  }
124 
125  ROS_INFO("Parameters read = %d", readCount);
126 
127  if(validParameters)
128  {
129  ROS_INFO("Parameters successfully read.");
130  }
131  else
132  {
133  if(this->isVisible())
134  {
135  QString warning = tr("Failed to get some RTAB-Map parameters from ROS server, the rtabmap node may be not started or some parameters won't work...");
136  ROS_WARN("%s", warning.toStdString().c_str());
137  QMessageBox::warning(this, tr("Can't read parameters from ROS server."), warning);
138  }
139  return false;
140  }
141  return true;
142 }
143 
144 void PreferencesDialogROS::writeCoreSettings(const QString & filePath) const
145 {
146  QString path = getIniFilePath();
147  if(!filePath.isEmpty())
148  {
149  path = filePath;
150  }
151 
152  if(QFile::exists(path))
153  {
154  rtabmap::ParametersMap parameters = this->getAllParameters();
155 
156  std::string workingDir = uValue(parameters, Parameters::kRtabmapWorkingDirectory(), std::string(""));
157 
158  if(!workingDir.empty())
159  {
160  //Just update GUI working directory
161  QSettings settings(path, QSettings::IniFormat);
162  settings.beginGroup("Core");
163  settings.remove("");
164  settings.setValue(Parameters::kRtabmapWorkingDirectory().c_str(), workingDir.c_str());
165  settings.endGroup();
166  }
167  }
168 }
169 
void setParameter(const std::string &key, const std::string &value)
rtabmap::ParametersMap getAllParameters() const
std::map< std::string, std::string > ParametersMap
virtual void writeCoreSettings(const QString &filePath) const
virtual bool readCoreSettings(const QString &filePath)
#define ROS_WARN(...)
#define ROS_INFO(...)
virtual QString getTmpIniFilePath() const
static const ParametersMap & getDefaultParameters()
virtual QString getParamMessage()
bool getParam(const std::string &key, std::string &s) const
virtual QString getIniFilePath() const
void setInputRate(double value)
PreferencesDialogROS(const QString &configFile)
virtual void readCameraSettings(const QString &filePath)
V uValue(const std::map< K, V > &m, const K &key, const V &defaultValue=V())


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:04