Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "rtabmap_ros/PreferencesDialogROS.h"
00029 #include <rtabmap/core/Parameters.h>
00030 #include <QDir>
00031 #include <QFileInfo>
00032 #include <QSettings>
00033 #include <QHBoxLayout>
00034 #include <QTimer>
00035 #include <QLabel>
00036 #include <rtabmap/core/RtabmapEvent.h>
00037 #include <QMessageBox>
00038 #include <ros/exceptions.h>
00039 #include <rtabmap/utilite/UStl.h>
00040
00041 using namespace rtabmap;
00042
00043 PreferencesDialogROS::PreferencesDialogROS(const QString & configFile) :
00044 configFile_(configFile)
00045 {
00046
00047 }
00048
00049 PreferencesDialogROS::~PreferencesDialogROS()
00050 {
00051 QFile::remove(getTmpIniFilePath());
00052 }
00053
00054 QString PreferencesDialogROS::getIniFilePath() const
00055 {
00056 if(configFile_.isEmpty())
00057 {
00058 return PreferencesDialog::getIniFilePath();
00059 }
00060 return configFile_;
00061 }
00062
00063 QString PreferencesDialogROS::getTmpIniFilePath() const
00064 {
00065 return QDir::homePath()+"/.ros/"+QFileInfo(configFile_).fileName()+".tmp";
00066 }
00067
00068 void PreferencesDialogROS::readCameraSettings(const QString & filePath)
00069 {
00070 this->setInputRate(0);
00071 }
00072
00073 QString PreferencesDialogROS::getParamMessage()
00074 {
00075 return tr("Reading parameters from the ROS server...");
00076 }
00077
00078 bool PreferencesDialogROS::readCoreSettings(const QString & filePath)
00079 {
00080 QString path = getIniFilePath();
00081 if(!filePath.isEmpty())
00082 {
00083 path = filePath;
00084 }
00085
00086 ros::NodeHandle nh;
00087 ROS_INFO("%s", this->getParamMessage().toStdString().c_str());
00088 bool validParameters = true;
00089 int readCount = 0;
00090 rtabmap::ParametersMap parameters = rtabmap::Parameters::getDefaultParameters();
00091 for(rtabmap::ParametersMap::iterator i=parameters.begin(); i!=parameters.end(); ++i)
00092 {
00093 if(i->first.compare(rtabmap::Parameters::kRtabmapWorkingDirectory()) == 0)
00094 {
00095
00096 QSettings settings(path, QSettings::IniFormat);
00097 settings.beginGroup("Core");
00098 QString value = settings.value(rtabmap::Parameters::kRtabmapWorkingDirectory().c_str(), "").toString();
00099 if(!value.isEmpty() && QDir(value).exists())
00100 {
00101 this->setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(), value.toStdString());
00102 }
00103 else
00104 {
00105
00106 this->setParameter(rtabmap::Parameters::kRtabmapWorkingDirectory(), (QDir::homePath()+"/.ros").toStdString());
00107 }
00108 settings.endGroup();
00109 }
00110 else
00111 {
00112 std::string value;
00113 if(nh.getParam(i->first,value))
00114 {
00115 PreferencesDialog::setParameter(i->first, value);
00116 ++readCount;
00117 }
00118 else
00119 {
00120 validParameters = false;
00121 }
00122 }
00123 }
00124
00125 ROS_INFO("Parameters read = %d", readCount);
00126
00127 if(validParameters)
00128 {
00129 ROS_INFO("Parameters successfully read.");
00130 }
00131 else
00132 {
00133 if(this->isVisible())
00134 {
00135 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...");
00136 ROS_WARN("%s", warning.toStdString().c_str());
00137 QMessageBox::warning(this, tr("Can't read parameters from ROS server."), warning);
00138 }
00139 return false;
00140 }
00141 return true;
00142 }
00143
00144 void PreferencesDialogROS::writeCoreSettings(const QString & filePath) const
00145 {
00146 QString path = getIniFilePath();
00147 if(!filePath.isEmpty())
00148 {
00149 path = filePath;
00150 }
00151
00152 if(QFile::exists(path))
00153 {
00154 rtabmap::ParametersMap parameters = this->getAllParameters();
00155
00156 std::string workingDir = uValue(parameters, Parameters::kRtabmapWorkingDirectory(), std::string(""));
00157
00158 if(!workingDir.empty())
00159 {
00160
00161 QSettings settings(path, QSettings::IniFormat);
00162 settings.beginGroup("Core");
00163 settings.remove("");
00164 settings.setValue(Parameters::kRtabmapWorkingDirectory().c_str(), workingDir.c_str());
00165 settings.endGroup();
00166 }
00167 }
00168 }
00169