33 #include <QHBoxLayout>
37 #include <QMessageBox>
46 configFile_(configFile),
47 rtabmapNodeName_(rtabmapNodeName)
61 return PreferencesDialog::getIniFilePath();
68 return QDir::homePath()+
"/.ros/"+QFileInfo(
configFile_).fileName()+
".tmp";
83 return tr(
"Reading parameters from the ROS server...");
90 for(rtabmap::ParametersMap::const_iterator
i=parameters.begin();
i!=parameters.end(); ++
i)
92 if(
i->first.compare(rtabmap::Parameters::kRtabmapWorkingDirectory()) != 0 &&
94 i->first.find(
"Odom") != 0)
104 for(rtabmap::ParametersMap::const_iterator
i=parameters.begin();
i!=parameters.end(); ++
i)
106 if(
i->first.compare(rtabmap::Parameters::kRtabmapWorkingDirectory()) != 0 &&
108 i->first.find(
"Odom") != 0)
119 if(!filePath.isEmpty())
126 bool validParameters =
true;
130 for(ParametersMap::iterator
iter=parameters.begin();
iter!=parameters.end();)
132 if(
iter->first.find(
"Odom") == 0)
134 parameters.erase(
iter++);
143 if(!this->isVisible())
152 ROS_INFO(
"rtabmap_viz: Cannot get rtabmap's parameters, waiting max 5 seconds in case the node has just been launched.");
161 ROS_INFO(
"rtabmap_viz: rtabmap's parameters seem now there! continuing...");
165 ROS_WARN(
"rtabmap_viz: rtabmap's parameters seem not all there yet! continuing with those there if some...");
170 for(rtabmap::ParametersMap::iterator
i=parameters.begin();
i!=parameters.end(); ++
i)
172 if(
i->first.compare(rtabmap::Parameters::kRtabmapWorkingDirectory()) == 0)
175 QSettings settings(
path, QSettings::IniFormat);
176 settings.beginGroup(
"Core");
177 QString
value = settings.value(rtabmap::Parameters::kRtabmapWorkingDirectory().
c_str(),
"").toString();
180 this->
setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(),
value.toStdString());
185 char * rosHomePath = getenv(
"ROS_HOME");
186 std::string workingDir = rosHomePath?rosHomePath:(QDir::homePath()+
"/.ros").toStdString();
187 this->
setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(), workingDir);
197 if(
i->first.compare(Parameters::kIcpStrategy()) == 0)
199 if(
value.compare(
"true") == 0)
203 else if(
value.compare(
"false") == 0)
209 PreferencesDialog::setParameter(
i->first,
value);
214 ROS_WARN(
"rtabmap_viz: Parameter %s not found",
i->first.c_str());
215 validParameters =
false;
220 ROS_INFO(
"rtabmap_viz: Parameters read = %d", readCount);
224 ROS_INFO(
"rtabmap_viz: Parameters successfully read.");
228 if(this->isVisible())
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);
242 if(!filePath.isEmpty())
247 if(QFile::exists(
path))
251 std::string workingDir =
uValue(parameters, Parameters::kRtabmapWorkingDirectory(), std::string(
""));
253 if(!workingDir.empty())
256 QSettings settings(
path, QSettings::IniFormat);
257 settings.beginGroup(
"Core");
259 settings.setValue(Parameters::kRtabmapWorkingDirectory().
c_str(), workingDir.c_str());