33 #include <QHBoxLayout> 37 #include <QMessageBox> 44 configFile_(configFile)
58 return PreferencesDialog::getIniFilePath();
65 return QDir::homePath()+
"/.ros/"+QFileInfo(
configFile_).fileName()+
".tmp";
75 return tr(
"Reading parameters from the ROS server...");
81 if(!filePath.isEmpty())
88 bool validParameters =
true;
91 for(rtabmap::ParametersMap::iterator i=parameters.begin(); i!=parameters.end(); ++i)
93 if(i->first.compare(rtabmap::Parameters::kRtabmapWorkingDirectory()) == 0)
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())
101 this->
setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(), value.toStdString());
106 this->
setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(), (QDir::homePath()+
"/.ros").toStdString());
115 PreferencesDialog::setParameter(i->first, value);
120 validParameters =
false;
125 ROS_INFO(
"Parameters read = %d", readCount);
129 ROS_INFO(
"Parameters successfully read.");
133 if(this->isVisible())
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);
147 if(!filePath.isEmpty())
152 if(QFile::exists(path))
156 std::string workingDir =
uValue(parameters, Parameters::kRtabmapWorkingDirectory(), std::string(
""));
158 if(!workingDir.empty())
161 QSettings settings(path, QSettings::IniFormat);
162 settings.beginGroup(
"Core");
164 settings.setValue(Parameters::kRtabmapWorkingDirectory().c_str(), workingDir.c_str());
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)
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)
virtual ~PreferencesDialogROS()
V uValue(const std::map< K, V > &m, const K &key, const V &defaultValue=V())