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 #include <rtabmap/utilite/UTimer.h>
42 
43 using namespace rtabmap;
44 
45 PreferencesDialogROS::PreferencesDialogROS(const QString & configFile, const std::string & rtabmapNodeName) :
46  configFile_(configFile),
47  rtabmapNodeName_(rtabmapNodeName)
48 {
49 
50 }
51 
53 {
54  QFile::remove(getTmpIniFilePath());
55 }
56 
58 {
59  if(configFile_.isEmpty())
60  {
61  return PreferencesDialog::getIniFilePath();
62  }
63  return configFile_;
64 }
65 
67 {
68  return QDir::homePath()+"/.ros/"+QFileInfo(configFile_).fileName()+".tmp";
69 }
70 
72 {
74 }
75 
76 void PreferencesDialogROS::readCameraSettings(const QString & filePath)
77 {
78  this->setInputRate(0);
79 }
80 
82 {
83  return tr("Reading parameters from the ROS server...");
84 }
85 
87 {
90  for(rtabmap::ParametersMap::const_iterator i=parameters.begin(); i!=parameters.end(); ++i)
91  {
92  if(i->first.compare(rtabmap::Parameters::kRtabmapWorkingDirectory()) != 0 && !nh.hasParam(i->first))
93  {
94  return false;
95  }
96  }
97  return true;
98 }
99 
101 {
102  for(rtabmap::ParametersMap::const_iterator i=parameters.begin(); i!=parameters.end(); ++i)
103  {
104  if(i->first.compare(rtabmap::Parameters::kRtabmapWorkingDirectory()) != 0 && !nh.hasParam(i->first))
105  {
106  return false;
107  }
108  }
109  return true;
110 }
111 
112 bool PreferencesDialogROS::readCoreSettings(const QString & filePath)
113 {
114  QString path = getIniFilePath();
115  if(!filePath.isEmpty())
116  {
117  path = filePath;
118  }
119 
121  ROS_INFO("rtabmapviz: %s", this->getParamMessage().toStdString().c_str());
122  bool validParameters = true;
123  int readCount = 0;
125  // remove Odom parameters
126  for(ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end();)
127  {
128  if(iter->first.find("Odom") == 0)
129  {
130  parameters.erase(iter++);
131  }
132  else
133  {
134  ++iter;
135  }
136  }
137 
138  // Wait rtabmap parameters to appear (if gui node has been launched at the same time than rtabmap)
139  if(!this->isVisible())
140  {
141  double stamp = UTimer::now();
142  std::string tmp;
143  bool warned = false;
144  while(!hasAllParameters(rnh, parameters) && UTimer::now()-stamp < 5.0)
145  {
146  if(!warned)
147  {
148  ROS_INFO("rtabmapviz: Cannot get rtabmap's parameters, waiting max 5 seconds in case the node has just been launched.");
149  warned = true;
150  }
151  uSleep(100);
152  }
153  if(warned)
154  {
155  if(UTimer::now()-stamp < 5.0)
156  {
157  ROS_INFO("rtabmapviz: rtabmap's parameters seem now there! continuing...");
158  }
159  else
160  {
161  ROS_WARN("rtabmapviz: rtabmap's parameters seem not all there yet! continuing with those there if some...");
162  }
163  }
164  }
165 
166  for(rtabmap::ParametersMap::iterator i=parameters.begin(); i!=parameters.end(); ++i)
167  {
168  if(i->first.compare(rtabmap::Parameters::kRtabmapWorkingDirectory()) == 0)
169  {
170  // use working directory of the GUI, not the one on rosparam server
171  QSettings settings(path, QSettings::IniFormat);
172  settings.beginGroup("Core");
173  QString value = settings.value(rtabmap::Parameters::kRtabmapWorkingDirectory().c_str(), "").toString();
174  if(!value.isEmpty() && QDir(value).exists())
175  {
176  this->setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(), value.toStdString());
177  }
178  else
179  {
180  // use default one
181  char * rosHomePath = getenv("ROS_HOME");
182  std::string workingDir = rosHomePath?rosHomePath:(QDir::homePath()+"/.ros").toStdString();
183  this->setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(), workingDir);
184  }
185  settings.endGroup();
186  }
187  else
188  {
189  std::string value;
190  if(rnh.getParam(i->first,value))
191  {
192  //backward compatibility
193  if(i->first.compare(Parameters::kIcpStrategy()) == 0)
194  {
195  if(value.compare("true") == 0)
196  {
197  value = "1";
198  }
199  else if(value.compare("false") == 0)
200  {
201  value = "0";
202  }
203  }
204 
205  PreferencesDialog::setParameter(i->first, value);
206  ++readCount;
207  }
208  else
209  {
210  ROS_WARN("rtabmapviz: Parameter %s not found", i->first.c_str());
211  validParameters = false;
212  }
213  }
214  }
215 
216  ROS_INFO("rtabmapviz: Parameters read = %d", readCount);
217 
218  if(validParameters)
219  {
220  ROS_INFO("rtabmapviz: Parameters successfully read.");
221  }
222  else
223  {
224  if(this->isVisible())
225  {
226  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...");
227  ROS_WARN("%s", warning.toStdString().c_str());
228  QMessageBox::warning(this, tr("Can't read parameters from ROS server."), warning);
229  }
230  return false;
231  }
232  return true;
233 }
234 
235 void PreferencesDialogROS::writeCoreSettings(const QString & filePath) const
236 {
237  QString path = getIniFilePath();
238  if(!filePath.isEmpty())
239  {
240  path = filePath;
241  }
242 
243  if(QFile::exists(path))
244  {
245  rtabmap::ParametersMap parameters = this->getAllParameters();
246 
247  std::string workingDir = uValue(parameters, Parameters::kRtabmapWorkingDirectory(), std::string(""));
248 
249  if(!workingDir.empty())
250  {
251  //Just update GUI working directory
252  QSettings settings(path, QSettings::IniFormat);
253  settings.beginGroup("Core");
254  settings.remove("");
255  settings.setValue(Parameters::kRtabmapWorkingDirectory().c_str(), workingDir.c_str());
256  settings.endGroup();
257  }
258  }
259 }
260 
void setParameter(const std::string &key, const std::string &value)
rtabmap::ParametersMap getAllParameters() const
virtual QString getIniFilePath() const
std::map< std::string, std::string > ParametersMap
virtual bool readCoreSettings(const QString &filePath)
virtual QString getTmpIniFilePath() const
#define ROS_WARN(...)
#define ROS_INFO(...)
bool getParam(const std::string &key, std::string &s) const
virtual void writeCoreSettings(const QString &filePath) const
bool hasParam(const std::string &key) const
void uSleep(unsigned int ms)
static const ParametersMap & getDefaultParameters()
virtual QString getParamMessage()
void setInputRate(double value)
bool isVisible(PanelDockWidget *widget)
static double now()
virtual void readCameraSettings(const QString &filePath)
PreferencesDialogROS(const QString &configFile, const std::string &rtabmapNodeName)
V uValue(const std::map< K, V > &m, const K &key, const V &defaultValue=V())


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40