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;
92 for(ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end();)
94 if(iter->first.find(
"Odom") == 0)
96 parameters.erase(iter++);
103 for(rtabmap::ParametersMap::iterator i=parameters.begin(); i!=parameters.end(); ++i)
105 if(i->first.compare(rtabmap::Parameters::kRtabmapWorkingDirectory()) == 0)
108 QSettings settings(path, QSettings::IniFormat);
109 settings.beginGroup(
"Core");
110 QString value = settings.value(rtabmap::Parameters::kRtabmapWorkingDirectory().c_str(),
"").toString();
111 if(!value.isEmpty() && QDir(value).exists())
113 this->
setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(), value.toStdString());
118 char * rosHomePath = getenv(
"ROS_HOME");
119 std::string workingDir = rosHomePath?rosHomePath:(QDir::homePath()+
"/.ros").toStdString();
120 this->
setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(), workingDir);
129 PreferencesDialog::setParameter(i->first, value);
134 ROS_WARN(
"Parameter %s not found", i->first.c_str());
135 validParameters =
false;
140 ROS_INFO(
"Parameters read = %d", readCount);
144 ROS_INFO(
"Parameters successfully read.");
148 if(this->isVisible())
150 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...");
151 ROS_WARN(
"%s", warning.toStdString().c_str());
152 QMessageBox::warning(
this, tr(
"Can't read parameters from ROS server."), warning);
162 if(!filePath.isEmpty())
167 if(QFile::exists(path))
171 std::string workingDir =
uValue(parameters, Parameters::kRtabmapWorkingDirectory(), std::string(
""));
173 if(!workingDir.empty())
176 QSettings settings(path, QSettings::IniFormat);
177 settings.beginGroup(
"Core");
179 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())