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 && !nh.
hasParam(i->first))
   102         for(rtabmap::ParametersMap::const_iterator i=parameters.begin(); i!=parameters.end(); ++i)
   104                 if(i->first.compare(rtabmap::Parameters::kRtabmapWorkingDirectory()) != 0 && !nh.
hasParam(i->first))
   115         if(!filePath.isEmpty())
   122         bool validParameters = 
true;
   126         for(ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end();)
   128                 if(iter->first.find(
"Odom") == 0)
   130                         parameters.erase(iter++);
   148                                 ROS_INFO(
"rtabmapviz: Cannot get rtabmap's parameters, waiting max 5 seconds in case the node has just been launched.");
   157                                 ROS_INFO(
"rtabmapviz: rtabmap's parameters seem now there! continuing...");
   161                                 ROS_WARN(
"rtabmapviz: rtabmap's parameters seem not all there yet! continuing with those there if some...");
   166         for(rtabmap::ParametersMap::iterator i=parameters.begin(); i!=parameters.end(); ++i)
   168                 if(i->first.compare(rtabmap::Parameters::kRtabmapWorkingDirectory()) == 0)
   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())
   176                                 this->
setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(), value.toStdString());
   181                                 char * rosHomePath = getenv(
"ROS_HOME");
   182                                 std::string workingDir = rosHomePath?rosHomePath:(QDir::homePath()+
"/.ros").toStdString();
   183                                 this->
setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(), workingDir);
   193                                 if(i->first.compare(Parameters::kIcpStrategy()) == 0)
   195                                         if(value.compare(
"true") == 0)
   199                                         else if(value.compare(
"false") == 0)
   205                                 PreferencesDialog::setParameter(i->first, value);
   210                                 ROS_WARN(
"rtabmapviz: Parameter %s not found", i->first.c_str());
   211                                 validParameters = 
false;
   216         ROS_INFO(
"rtabmapviz: Parameters read = %d", readCount);
   220                 ROS_INFO(
"rtabmapviz: Parameters successfully read.");
   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);
   238         if(!filePath.isEmpty())
   243         if(QFile::exists(path))
   247                 std::string workingDir = 
uValue(parameters, Parameters::kRtabmapWorkingDirectory(), std::string(
""));
   249                 if(!workingDir.empty())
   252                         QSettings settings(path, QSettings::IniFormat);
   253                         settings.beginGroup(
"Core");
   255                         settings.setValue(Parameters::kRtabmapWorkingDirectory().c_str(), workingDir.c_str());
 void readRtabmapNodeParameters()
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
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()
std::string rtabmapNodeName_
void setInputRate(double value)
bool isVisible(PanelDockWidget *widget)
virtual void readCameraSettings(const QString &filePath)
virtual ~PreferencesDialogROS()
PreferencesDialogROS(const QString &configFile, const std::string &rtabmapNodeName)
V uValue(const std::map< K, V > &m, const K &key, const V &defaultValue=V())