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


rtabmap_viz
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:45:31