Parameters.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include "rtabmap/core/Parameters.h"
00029 #include <rtabmap/utilite/UDirectory.h>
00030 #include <rtabmap/utilite/ULogger.h>
00031 #include <rtabmap/utilite/UConversion.h>
00032 #include <rtabmap/utilite/UStl.h>
00033 #include <cmath>
00034 #include <stdlib.h>
00035 #include <sstream>
00036 #include <iostream>
00037 #include <iomanip>
00038 #include "SimpleIni.h"
00039 
00040 namespace rtabmap
00041 {
00042 
00043 ParametersMap Parameters::parameters_;
00044 ParametersMap Parameters::parametersType_;
00045 ParametersMap Parameters::descriptions_;
00046 Parameters Parameters::instance_;
00047 std::map<std::string, std::pair<bool, std::string> > Parameters::removedParameters_;
00048 ParametersMap Parameters::backwardCompatibilityMap_;
00049 
00050 Parameters::Parameters()
00051 {
00052 }
00053 
00054 Parameters::~Parameters()
00055 {
00056 }
00057 
00058 std::string Parameters::createDefaultWorkingDirectory()
00059 {
00060         std::string path = UDirectory::homeDir();
00061         if(!path.empty())
00062         {
00063                 UDirectory::makeDir(path += UDirectory::separator() + "Documents");
00064                 UDirectory::makeDir(path += UDirectory::separator() + "RTAB-Map");
00065 
00066         }
00067         else
00068         {
00069                 UFATAL("Can't get the HOME variable environment!");
00070         }
00071         return path;
00072 }
00073 
00074 std::string Parameters::getVersion()
00075 {
00076         return RTABMAP_VERSION;
00077         return ""; // Second return only to avoid compiler warning with RTABMAP_VERSION not yet set.
00078 }
00079 
00080 std::string Parameters::getDefaultDatabaseName()
00081 {
00082         return "rtabmap.db";
00083 }
00084 
00085 std::string Parameters::serialize(const ParametersMap & parameters)
00086 {
00087         std::stringstream output;
00088         for(ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
00089         {
00090                 if(iter != parameters.begin())
00091                 {
00092                         output << ";";
00093                 }
00094                 // make sure there are no commas instead of dots
00095                 output << iter->first << ":" << uReplaceChar(iter->second, ',', '.');
00096         }
00097         UDEBUG("output=%s", output.str().c_str());
00098         return output.str();
00099 }
00100 
00101 ParametersMap Parameters::deserialize(const std::string & parameters)
00102 {
00103         UDEBUG("parameters=%s", parameters.c_str());
00104         ParametersMap output;
00105         std::list<std::string> tuplets = uSplit(parameters, ';');
00106         for(std::list<std::string>::iterator iter=tuplets.begin(); iter!=tuplets.end(); ++iter)
00107         {
00108                 std::list<std::string> p = uSplit(*iter, ':');
00109                 if(p.size() == 2)
00110                 {
00111                         std::string key = p.front();
00112                         std::string value = p.back();
00113 
00114                         // look for old parameter name
00115                         bool addParameter = true;
00116                         std::map<std::string, std::pair<bool, std::string> >::const_iterator oldIter = Parameters::getRemovedParameters().find(key);
00117                         if(oldIter!=Parameters::getRemovedParameters().end())
00118                         {
00119                                 addParameter = oldIter->second.first;
00120                                 if(addParameter)
00121                                 {
00122                                         key = oldIter->second.second;
00123                                         UWARN("Parameter migration from \"%s\" to \"%s\" (value=%s).",
00124                                                         oldIter->first.c_str(), oldIter->second.second.c_str(), value.c_str());
00125                                 }
00126                                 else if(oldIter->second.second.empty())
00127                                 {
00128                                         UWARN("Parameter \"%s\" doesn't exist anymore.",
00129                                                                 oldIter->first.c_str());
00130                                 }
00131                                 else
00132                                 {
00133                                         UWARN("Parameter \"%s\" doesn't exist anymore, you may want to use this similar parameter \"%s\":\"%s\".",
00134                                                                 oldIter->first.c_str(), oldIter->second.second.c_str(), Parameters::getDescription(oldIter->second.second).c_str());
00135                                 }
00136 
00137                         }
00138 
00139                         if(oldIter==Parameters::getRemovedParameters().end() &&
00140                            Parameters::getDefaultParameters().find(key) == Parameters::getDefaultParameters().end())
00141                         {
00142                                 UWARN("Unknown parameter \"%s\"=\"%s\"! The parameter is still added to output map.", key.c_str(), value.c_str());
00143                         }
00144                         uInsert(output, ParametersPair(key, value));
00145                 }
00146         }
00147         return output;
00148 }
00149 
00150 bool Parameters::isFeatureParameter(const std::string & parameter)
00151 {
00152         std::string group = uSplit(parameter, '/').front();
00153         return  group.compare("SURF") == 0 ||
00154                         group.compare("SIFT") == 0 ||
00155                         group.compare("ORB") == 0 ||
00156                         group.compare("FAST") == 0 ||
00157                         group.compare("FREAK") == 0 ||
00158                         group.compare("BRIEF") == 0 ||
00159                         group.compare("GFTT") == 0 ||
00160                         group.compare("BRISK") == 0 ||
00161                         group.compare("KAZE") == 0;
00162 }
00163 
00164 rtabmap::ParametersMap Parameters::getDefaultOdometryParameters(bool stereo, bool vis, bool icp)
00165 {
00166         rtabmap::ParametersMap odomParameters;
00167         rtabmap::ParametersMap defaultParameters = rtabmap::Parameters::getDefaultParameters();
00168         for(rtabmap::ParametersMap::iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
00169         {
00170                 std::string group = uSplit(iter->first, '/').front();
00171                 if(uStrContains(group, "Odom") ||
00172                         (stereo && group.compare("Stereo") == 0) ||
00173                         (icp && group.compare("Icp") == 0) ||
00174                         (vis && Parameters::isFeatureParameter(iter->first)) ||
00175                         group.compare("Reg") == 0 ||
00176                         (vis && group.compare("Vis") == 0) ||
00177                         iter->first.compare(kRtabmapPublishRAMUsage())==0)
00178                 {
00179                         if(stereo)
00180                         {
00181                                 if(iter->first.compare(Parameters::kVisEstimationType()) == 0)
00182                                 {
00183                                         iter->second = "1"; // 3D->2D (PNP)
00184                                 }
00185                         }
00186                         odomParameters.insert(*iter);
00187                 }
00188         }
00189         return odomParameters;
00190 }
00191 
00192 ParametersMap Parameters::getDefaultParameters(const std::string & groupIn)
00193 {
00194         rtabmap::ParametersMap parameters;
00195         const rtabmap::ParametersMap & defaultParameters = rtabmap::Parameters::getDefaultParameters();
00196         for(rtabmap::ParametersMap::const_iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
00197         {
00198                 UASSERT(uSplit(iter->first, '/').size()  == 2);
00199                 std::string group = uSplit(iter->first, '/').front();
00200                 if(group.compare(groupIn) == 0)
00201                 {
00202                         parameters.insert(*iter);
00203                 }
00204         }
00205         UASSERT_MSG(parameters.size(), uFormat("No parameters found for group %s!", groupIn.c_str()).c_str());
00206         return parameters;
00207 }
00208 
00209 ParametersMap Parameters::filterParameters(const ParametersMap & parameters, const std::string & groupIn)
00210 {
00211         ParametersMap output;
00212         for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
00213         {
00214                 UASSERT(uSplit(iter->first, '/').size()  == 2);
00215                 std::string group = uSplit(iter->first, '/').front();
00216                 if(group.compare(groupIn) == 0)
00217                 {
00218                         output.insert(*iter);
00219                 }
00220         }
00221         return output;
00222 }
00223 
00224 const std::map<std::string, std::pair<bool, std::string> > & Parameters::getRemovedParameters()
00225 {
00226         if(removedParameters_.empty())
00227         {
00228                 // removed parameters
00229 
00230                 // 0.17.5
00231                 removedParameters_.insert(std::make_pair("Grid/OctoMapOccupancyThr",     std::make_pair(true,  Parameters::kGridGlobalOccupancyThr())));
00232 
00233                 // 0.17.0
00234                 removedParameters_.insert(std::make_pair("Grid/Scan2dMaxFilledRange",     std::make_pair(false,  Parameters::kGridRangeMax())));
00235 
00236                 // 0.16.0
00237                 removedParameters_.insert(std::make_pair("Grid/ProjRayTracing",           std::make_pair(true,  Parameters::kGridRayTracing())));
00238                 removedParameters_.insert(std::make_pair("Grid/DepthMin",                 std::make_pair(true,  Parameters::kGridRangeMin())));
00239                 removedParameters_.insert(std::make_pair("Grid/DepthMax",                 std::make_pair(true,  Parameters::kGridRangeMax())));
00240 
00241                 // 0.15.1
00242                 removedParameters_.insert(std::make_pair("Reg/VarianceFromInliersCount",  std::make_pair(false, "")));
00243                 removedParameters_.insert(std::make_pair("Reg/VarianceNormalized",        std::make_pair(false, "")));
00244 
00245                 // 0.13.3
00246                 removedParameters_.insert(std::make_pair("Icp/PointToPlaneNormalNeighbors", std::make_pair(true,  Parameters::kIcpPointToPlaneK())));
00247 
00248 
00249                 // 0.13.1
00250                 removedParameters_.insert(std::make_pair("Rtabmap/VhStrategy",            std::make_pair(true,  Parameters::kVhEpEnabled())));
00251 
00252                 // 0.12.5
00253                 removedParameters_.insert(std::make_pair("Grid/FullUpdate",               std::make_pair(true,  Parameters::kGridGlobalFullUpdate())));
00254 
00255                 // 0.12.1
00256                 removedParameters_.insert(std::make_pair("Grid/3DGroundIsObstacle",       std::make_pair(true,  Parameters::kGridGroundIsObstacle())));
00257 
00258                 // 0.11.12
00259                 removedParameters_.insert(std::make_pair("Optimizer/Slam2D",              std::make_pair(true,  Parameters::kRegForce3DoF())));
00260                 removedParameters_.insert(std::make_pair("OdomF2M/FixedMapPath",          std::make_pair(false,  "")));
00261 
00262                 // 0.11.10 typos
00263                 removedParameters_.insert(std::make_pair("Grid/FlatObstaclesDetected",    std::make_pair(true,  Parameters::kGridFlatObstacleDetected())));
00264 
00265                 // 0.11.8
00266                 removedParameters_.insert(std::make_pair("Reg/Force2D",                   std::make_pair(true,  Parameters::kRegForce3DoF())));
00267                 removedParameters_.insert(std::make_pair("OdomF2M/ScanSubstractRadius",   std::make_pair(true,  Parameters::kOdomF2MScanSubtractRadius())));
00268 
00269                 // 0.11.6
00270                 removedParameters_.insert(std::make_pair("RGBD/ProximityPathScansMerged", std::make_pair(false,  "")));
00271 
00272                 // 0.11.3
00273                 removedParameters_.insert(std::make_pair("Mem/ImageDecimation",           std::make_pair(true, Parameters::kMemImagePostDecimation())));
00274 
00275                 // 0.11.2
00276                 removedParameters_.insert(std::make_pair("OdomLocalMap/HistorySize",      std::make_pair(true, Parameters::kOdomF2MMaxSize())));
00277                 removedParameters_.insert(std::make_pair("OdomLocalMap/FixedMapPath",     std::make_pair(false, "")));
00278                 removedParameters_.insert(std::make_pair("OdomF2F/GuessMotion",           std::make_pair(true, Parameters::kOdomGuessMotion())));
00279                 removedParameters_.insert(std::make_pair("OdomF2F/KeyFrameThr",           std::make_pair(false, Parameters::kOdomKeyFrameThr())));
00280 
00281                 // 0.11.0
00282                 removedParameters_.insert(std::make_pair("OdomBow/LocalHistorySize",      std::make_pair(true, Parameters::kOdomF2MMaxSize())));
00283                 removedParameters_.insert(std::make_pair("OdomBow/FixedLocalMapPath",     std::make_pair(false, "")));
00284                 removedParameters_.insert(std::make_pair("OdomFlow/KeyFrameThr",          std::make_pair(false, Parameters::kOdomKeyFrameThr())));
00285                 removedParameters_.insert(std::make_pair("OdomFlow/GuessMotion",          std::make_pair(true, Parameters::kOdomGuessMotion())));
00286 
00287                 removedParameters_.insert(std::make_pair("Kp/WordsPerImage",              std::make_pair(true, Parameters::kKpMaxFeatures())));
00288 
00289                 removedParameters_.insert(std::make_pair("Mem/LocalSpaceLinksKeptInWM",   std::make_pair(false, "")));
00290 
00291                 removedParameters_.insert(std::make_pair("RGBD/PoseScanMatching",         std::make_pair(true,  Parameters::kRGBDNeighborLinkRefining())));
00292 
00293                 removedParameters_.insert(std::make_pair("Odom/ParticleFiltering",        std::make_pair(false, Parameters::kOdomFilteringStrategy())));
00294                 removedParameters_.insert(std::make_pair("Odom/FeatureType",              std::make_pair(true,  Parameters::kVisFeatureType())));
00295                 removedParameters_.insert(std::make_pair("Odom/EstimationType",           std::make_pair(true,  Parameters::kVisEstimationType())));
00296                 removedParameters_.insert(std::make_pair("Odom/MaxFeatures",              std::make_pair(true,  Parameters::kVisMaxFeatures())));
00297                 removedParameters_.insert(std::make_pair("Odom/InlierDistance",           std::make_pair(true,  Parameters::kVisInlierDistance())));
00298                 removedParameters_.insert(std::make_pair("Odom/MinInliers",               std::make_pair(true,  Parameters::kVisMinInliers())));
00299                 removedParameters_.insert(std::make_pair("Odom/Iterations",               std::make_pair(true,  Parameters::kVisIterations())));
00300                 removedParameters_.insert(std::make_pair("Odom/RefineIterations",         std::make_pair(true,  Parameters::kVisRefineIterations())));
00301                 removedParameters_.insert(std::make_pair("Odom/MaxDepth",                 std::make_pair(true,  Parameters::kVisMaxDepth())));
00302                 removedParameters_.insert(std::make_pair("Odom/RoiRatios",                std::make_pair(true,  Parameters::kVisRoiRatios())));
00303                 removedParameters_.insert(std::make_pair("Odom/Force2D",                  std::make_pair(true,  Parameters::kRegForce3DoF())));
00304                 removedParameters_.insert(std::make_pair("Odom/VarianceFromInliersCount", std::make_pair(false, "")));
00305                 removedParameters_.insert(std::make_pair("Odom/PnPReprojError",           std::make_pair(true,  Parameters::kVisPnPReprojError())));
00306                 removedParameters_.insert(std::make_pair("Odom/PnPFlags",                 std::make_pair(true,  Parameters::kVisPnPFlags())));
00307 
00308                 removedParameters_.insert(std::make_pair("OdomBow/NNType",                std::make_pair(true,  Parameters::kVisCorNNType())));
00309                 removedParameters_.insert(std::make_pair("OdomBow/NNDR",                  std::make_pair(true,  Parameters::kVisCorNNDR())));
00310 
00311                 removedParameters_.insert(std::make_pair("OdomFlow/WinSize",              std::make_pair(true,  Parameters::kVisCorFlowWinSize())));
00312                 removedParameters_.insert(std::make_pair("OdomFlow/Iterations",           std::make_pair(true,  Parameters::kVisCorFlowIterations())));
00313                 removedParameters_.insert(std::make_pair("OdomFlow/Eps",                  std::make_pair(true,  Parameters::kVisCorFlowEps())));
00314                 removedParameters_.insert(std::make_pair("OdomFlow/MaxLevel",             std::make_pair(true,  Parameters::kVisCorFlowMaxLevel())));
00315 
00316                 removedParameters_.insert(std::make_pair("OdomSubPix/WinSize",            std::make_pair(true,  Parameters::kVisSubPixWinSize())));
00317                 removedParameters_.insert(std::make_pair("OdomSubPix/Iterations",         std::make_pair(true,  Parameters::kVisSubPixIterations())));
00318                 removedParameters_.insert(std::make_pair("OdomSubPix/Eps",                std::make_pair(true,  Parameters::kVisSubPixEps())));
00319 
00320                 removedParameters_.insert(std::make_pair("LccReextract/Activated",         std::make_pair(true,   Parameters::kRGBDLoopClosureReextractFeatures())));
00321                 removedParameters_.insert(std::make_pair("LccReextract/FeatureType",       std::make_pair(false,  Parameters::kVisFeatureType())));
00322                 removedParameters_.insert(std::make_pair("LccReextract/MaxWords",          std::make_pair(false,  Parameters::kVisMaxFeatures())));
00323                 removedParameters_.insert(std::make_pair("LccReextract/MaxDepth",          std::make_pair(false,  Parameters::kVisMaxDepth())));
00324                 removedParameters_.insert(std::make_pair("LccReextract/RoiRatios",         std::make_pair(false,  Parameters::kVisRoiRatios())));
00325                 removedParameters_.insert(std::make_pair("LccReextract/NNType",            std::make_pair(false,  Parameters::kVisCorNNType())));
00326                 removedParameters_.insert(std::make_pair("LccReextract/NNDR",              std::make_pair(false,  Parameters::kVisCorNNDR())));
00327 
00328                 removedParameters_.insert(std::make_pair("LccBow/EstimationType",           std::make_pair(false,  Parameters::kVisEstimationType())));
00329                 removedParameters_.insert(std::make_pair("LccBow/InlierDistance",           std::make_pair(false,  Parameters::kVisInlierDistance())));
00330                 removedParameters_.insert(std::make_pair("LccBow/MinInliers",               std::make_pair(false,  Parameters::kVisMinInliers())));
00331                 removedParameters_.insert(std::make_pair("LccBow/Iterations",               std::make_pair(false,  Parameters::kVisIterations())));
00332                 removedParameters_.insert(std::make_pair("LccBow/RefineIterations",         std::make_pair(false,  Parameters::kVisRefineIterations())));
00333                 removedParameters_.insert(std::make_pair("LccBow/Force2D",                  std::make_pair(false,  Parameters::kRegForce3DoF())));
00334                 removedParameters_.insert(std::make_pair("LccBow/VarianceFromInliersCount", std::make_pair(false,  "")));
00335                 removedParameters_.insert(std::make_pair("LccBow/PnPReprojError",           std::make_pair(false,  Parameters::kVisPnPReprojError())));
00336                 removedParameters_.insert(std::make_pair("LccBow/PnPFlags",                 std::make_pair(false,  Parameters::kVisPnPFlags())));
00337                 removedParameters_.insert(std::make_pair("LccBow/EpipolarGeometryVar",      std::make_pair(true,   Parameters::kVisEpipolarGeometryVar())));
00338 
00339                 removedParameters_.insert(std::make_pair("LccIcp/Type",                         std::make_pair(false,  Parameters::kRegStrategy())));
00340 
00341                 removedParameters_.insert(std::make_pair("LccIcp3/Decimation",                  std::make_pair(false, "")));
00342                 removedParameters_.insert(std::make_pair("LccIcp3/MaxDepth",                    std::make_pair(false, "")));
00343                 removedParameters_.insert(std::make_pair("LccIcp3/VoxelSize",                   std::make_pair(false, Parameters::kIcpVoxelSize())));
00344                 removedParameters_.insert(std::make_pair("LccIcp3/Samples",                     std::make_pair(false, Parameters::kIcpDownsamplingStep())));
00345                 removedParameters_.insert(std::make_pair("LccIcp3/MaxCorrespondenceDistance",   std::make_pair(false, Parameters::kIcpMaxCorrespondenceDistance())));
00346                 removedParameters_.insert(std::make_pair("LccIcp3/Iterations",                  std::make_pair(false, Parameters::kIcpIterations())));
00347                 removedParameters_.insert(std::make_pair("LccIcp3/CorrespondenceRatio",         std::make_pair(false, Parameters::kIcpCorrespondenceRatio())));
00348                 removedParameters_.insert(std::make_pair("LccIcp3/PointToPlane",                std::make_pair(true,  Parameters::kIcpPointToPlane())));
00349                 removedParameters_.insert(std::make_pair("LccIcp3/PointToPlaneNormalNeighbors", std::make_pair(true,  Parameters::kIcpPointToPlaneK())));
00350 
00351                 removedParameters_.insert(std::make_pair("LccIcp2/MaxCorrespondenceDistance",   std::make_pair(true,  Parameters::kIcpMaxCorrespondenceDistance())));
00352                 removedParameters_.insert(std::make_pair("LccIcp2/Iterations",                  std::make_pair(true,  Parameters::kIcpIterations())));
00353                 removedParameters_.insert(std::make_pair("LccIcp2/CorrespondenceRatio",         std::make_pair(true,  Parameters::kIcpCorrespondenceRatio())));
00354                 removedParameters_.insert(std::make_pair("LccIcp2/VoxelSize",                   std::make_pair(true,  Parameters::kIcpVoxelSize())));
00355 
00356                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionByTime",              std::make_pair(true,  Parameters::kRGBDProximityByTime())));
00357                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionBySpace",             std::make_pair(true,  Parameters::kRGBDProximityBySpace())));
00358                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionTime",                std::make_pair(true,  Parameters::kRGBDProximityByTime())));
00359                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionSpace",               std::make_pair(true,  Parameters::kRGBDProximityBySpace())));
00360                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathScansMerged",     std::make_pair(false,  "")));
00361                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxGraphDepth",       std::make_pair(true,  Parameters::kRGBDProximityMaxGraphDepth())));
00362                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathFilteringRadius", std::make_pair(true,  Parameters::kRGBDProximityPathFilteringRadius())));
00363                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathRawPosesUsed",    std::make_pair(true,  Parameters::kRGBDProximityPathRawPosesUsed())));
00364 
00365                 removedParameters_.insert(std::make_pair("RGBD/OptimizeStrategy",             std::make_pair(true,  Parameters::kOptimizerStrategy())));
00366                 removedParameters_.insert(std::make_pair("RGBD/OptimizeEpsilon",             std::make_pair(true,  Parameters::kOptimizerEpsilon())));
00367                 removedParameters_.insert(std::make_pair("RGBD/OptimizeIterations",          std::make_pair(true,  Parameters::kOptimizerIterations())));
00368                 removedParameters_.insert(std::make_pair("RGBD/OptimizeRobust",              std::make_pair(true,  Parameters::kOptimizerRobust())));
00369                 removedParameters_.insert(std::make_pair("RGBD/OptimizeSlam2D",              std::make_pair(true,  Parameters::kRegForce3DoF())));
00370                 removedParameters_.insert(std::make_pair("RGBD/OptimizeSlam2d",              std::make_pair(true,  Parameters::kRegForce3DoF())));
00371                 removedParameters_.insert(std::make_pair("RGBD/OptimizeVarianceIgnored",     std::make_pair(true,  Parameters::kOptimizerVarianceIgnored())));
00372 
00373                 removedParameters_.insert(std::make_pair("Stereo/WinSize",                   std::make_pair(true,  Parameters::kStereoWinWidth())));
00374 
00375                 // before 0.11.0
00376                 removedParameters_.insert(std::make_pair("GFTT/MaxCorners",                  std::make_pair(true, Parameters::kVisMaxFeatures())));
00377                 removedParameters_.insert(std::make_pair("LccBow/MaxDepth",                  std::make_pair(true, Parameters::kVisMaxDepth())));
00378                 removedParameters_.insert(std::make_pair("LccReextract/LoopClosureFeatures", std::make_pair(true, Parameters::kRGBDLoopClosureReextractFeatures())));
00379                 removedParameters_.insert(std::make_pair("Rtabmap/DetectorStrategy",         std::make_pair(true, Parameters::kKpDetectorStrategy())));
00380                 removedParameters_.insert(std::make_pair("RGBD/ScanMatchingSize",            std::make_pair(true, Parameters::kRGBDNeighborLinkRefining())));
00381                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionRadius",    std::make_pair(true, Parameters::kRGBDLocalRadius())));
00382                 removedParameters_.insert(std::make_pair("RGBD/ToroIterations",              std::make_pair(true, Parameters::kOptimizerIterations())));
00383                 removedParameters_.insert(std::make_pair("Mem/RehearsedNodesKept",           std::make_pair(true, Parameters::kMemNotLinkedNodesKept())));
00384                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(true, Parameters::kRGBDProximityMaxGraphDepth())));
00385                 removedParameters_.insert(std::make_pair("RGBD/PlanVirtualLinksMaxDiffID",   std::make_pair(false, "")));
00386                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(false, "")));
00387                 removedParameters_.insert(std::make_pair("Odom/Type",                        std::make_pair(true, Parameters::kVisFeatureType())));
00388                 removedParameters_.insert(std::make_pair("Odom/MaxWords",                    std::make_pair(true, Parameters::kVisMaxFeatures())));
00389                 removedParameters_.insert(std::make_pair("Odom/LocalHistory",                std::make_pair(true, Parameters::kOdomF2MMaxSize())));
00390                 removedParameters_.insert(std::make_pair("Odom/NearestNeighbor",             std::make_pair(true, Parameters::kVisCorNNType())));
00391                 removedParameters_.insert(std::make_pair("Odom/NNDR",                        std::make_pair(true, Parameters::kVisCorNNDR())));
00392         }
00393         return removedParameters_;
00394 }
00395 
00396 const ParametersMap & Parameters::getBackwardCompatibilityMap()
00397 {
00398         if(backwardCompatibilityMap_.empty())
00399         {
00400                 getRemovedParameters(); // make sure removedParameters is filled
00401 
00402                 // compatibility
00403                 for(std::map<std::string, std::pair<bool, std::string> >::iterator iter=removedParameters_.begin();
00404                         iter!=removedParameters_.end();
00405                         ++iter)
00406                 {
00407                         if(iter->second.first)
00408                         {
00409                                 backwardCompatibilityMap_.insert(ParametersPair(iter->second.second, iter->first));
00410                         }
00411                 }
00412         }
00413         return backwardCompatibilityMap_;
00414 }
00415 
00416 std::string Parameters::getType(const std::string & paramKey)
00417 {
00418         std::string type;
00419         ParametersMap::iterator iter = parametersType_.find(paramKey);
00420         if(iter != parametersType_.end())
00421         {
00422                 type = iter->second;
00423         }
00424         else
00425         {
00426                 UERROR("Parameters \"%s\" doesn't exist!", paramKey.c_str());
00427         }
00428         return type;
00429 }
00430 
00431 std::string Parameters::getDescription(const std::string & paramKey)
00432 {
00433         std::string description;
00434         ParametersMap::iterator iter = descriptions_.find(paramKey);
00435         if(iter != descriptions_.end())
00436         {
00437                 description = iter->second;
00438         }
00439         else
00440         {
00441                 UERROR("Parameters \"%s\" doesn't exist!", paramKey.c_str());
00442         }
00443         return description;
00444 }
00445 
00446 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, bool & value)
00447 {
00448         ParametersMap::const_iterator iter = parameters.find(key);
00449         if(iter != parameters.end())
00450         {
00451                 value = uStr2Bool(iter->second.c_str());
00452                 return true;
00453         }
00454         return false;
00455 }
00456 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, int & value)
00457 {
00458         ParametersMap::const_iterator iter = parameters.find(key);
00459         if(iter != parameters.end())
00460         {
00461                 value = uStr2Int(iter->second.c_str());
00462                 return true;
00463         }
00464         return false;
00465 }
00466 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, unsigned int & value)
00467 {
00468         ParametersMap::const_iterator iter = parameters.find(key);
00469         if(iter != parameters.end())
00470         {
00471                 value = uStr2Int(iter->second.c_str());
00472                 return true;
00473         }
00474         return false;
00475 }
00476 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, float & value)
00477 {
00478         ParametersMap::const_iterator iter = parameters.find(key);
00479         if(iter != parameters.end())
00480         {
00481                 value = uStr2Float(iter->second);
00482                 return true;
00483         }
00484         return false;
00485 }
00486 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, double & value)
00487 {
00488         ParametersMap::const_iterator iter = parameters.find(key);
00489         if(iter != parameters.end())
00490         {
00491                 value = uStr2Double(iter->second);
00492                 return true;
00493         }
00494         return false;
00495 }
00496 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, std::string & value)
00497 {
00498         ParametersMap::const_iterator iter = parameters.find(key);
00499         if(iter != parameters.end())
00500         {
00501                 value = iter->second;
00502                 return true;
00503         }
00504         return false;
00505 }
00506 void Parameters::parse(const ParametersMap & parameters, ParametersMap & parametersOut)
00507 {
00508         for(ParametersMap::iterator iter=parametersOut.begin(); iter!=parametersOut.end(); ++iter)
00509         {
00510                 ParametersMap::const_iterator jter = parameters.find(iter->first);
00511                 if(jter != parameters.end())
00512                 {
00513                         iter->second = jter->second;
00514                 }
00515         }
00516 }
00517 
00518 const char * Parameters::showUsage()
00519 {
00520         return  "RTAB-Map options:\n"
00521                         "   --help                         Show usage.\n"
00522                         "   --version                      Show version of rtabmap and its dependencies.\n"
00523                         "   --params                       Show all parameters with their default value and description\n"
00524                         "   --\"parameter name\" \"value\"     Overwrite a specific RTAB-Map's parameter :\n"
00525                         "                                    --SURF/HessianThreshold 150\n"
00526                         "                                   For parameters in table format, add ',' between values :\n"
00527                         "                                    --Kp/RoiRatios 0,0,0.1,0\n"
00528                         "Logger options:\n"
00529                         "   --nolog              Disable logger\n"
00530                         "   --logconsole         Set logger console type\n"
00531                         "   --logfile \"path\"     Set logger file type\n"
00532                         "   --logfilea \"path\"    Set logger file type with appending mode if the file already exists\n"
00533                         "   --udebug             Set logger level to debug\n"
00534                         "   --uinfo              Set logger level to info\n"
00535                         "   --uwarn              Set logger level to warn\n"
00536                         "   --uerror             Set logger level to error\n"
00537                         "   --logtime \"bool\"     Print time when logging\n"
00538                         "   --logwhere \"bool\"    Print where when logging\n"
00539                         "   --logthread \"bool\"   Print thread id when logging\n"
00540                         ;
00541 }
00542 
00543 ParametersMap Parameters::parseArguments(int argc, char * argv[], bool onlyParameters)
00544 {
00545         ParametersMap out;
00546         const ParametersMap & parameters = getDefaultParameters();
00547         const std::map<std::string, std::pair<bool, std::string> > & removedParams = getRemovedParameters();
00548         for(int i=0;i<argc;++i)
00549         {
00550                 bool checkParameters = onlyParameters;
00551                 if(!checkParameters)
00552                 {
00553                         if(strcmp(argv[i], "--help") == 0)
00554                         {
00555                                 std::cout << showUsage() << std::endl;
00556                                 exit(0);
00557                         }
00558                         else if(strcmp(argv[i], "--version") == 0)
00559                         {
00560                                 std::string str = "RTAB-Map:";
00561 
00562                                 int spacing = 30;
00563                                 std::cout << str << std::setw(spacing - str.size()) << RTABMAP_VERSION << std::endl;
00564                                 str = "OpenCV:";
00565 #ifdef RTABMAP_OPENCV3
00566                                 std::cout << str << std::setw(spacing - str.size()) << "3" << std::endl;
00567 #else
00568                                 std::cout << str << std::setw(spacing - str.size()) << "2" << std::endl;
00569 #endif
00570                                 str = "With OpenCV nonfree:";
00571 #ifdef RTABMAP_NONFREE
00572                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00573 #else
00574                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00575 #endif
00576                                 str = "With TORO:";
00577 #ifdef RTABMAP_TORO
00578                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00579 #else
00580                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00581 #endif
00582                                 str = "With g2o:";
00583 #ifdef RTABMAP_G2O
00584                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00585 #else
00586                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00587 #endif
00588                                 str = "With GTSAM:";
00589 #ifdef RTABMAP_GTSAM
00590                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00591 #else
00592                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00593 #endif
00594                                 str = "With Vertigo:";
00595 #ifdef RTABMAP_VERTIGO
00596                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00597 #else
00598                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00599 #endif
00600                                 str = "With CVSBA:";
00601 #ifdef RTABMAP_CVSBA
00602                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00603 #else
00604                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00605 #endif
00606                                 str = "With OpenNI2:";
00607 #ifdef RTABMAP_OPENNI2
00608                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00609 #else
00610                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00611 #endif
00612                                 str = "With Freenect:";
00613 #ifdef RTABMAP_FREENECT
00614                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00615 #else
00616                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00617 #endif
00618                                 str = "With Freenect2:";
00619 #ifdef RTABMAP_FREENECT2
00620                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00621 #else
00622                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00623 #endif
00624                                 str = "With K4W2:";
00625 #ifdef RTABMAP_K4W2
00626                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00627 #else
00628                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00629 #endif
00630                                 str = "With DC1394:";
00631 #ifdef RTABMAP_DC1394
00632                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00633 #else
00634                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00635 #endif
00636                                 str = "With FlyCapture2:";
00637 #ifdef RTABMAP_FLYCAPTURE2
00638                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00639 #else
00640                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00641 #endif
00642                                 str = "With ZED:";
00643 #ifdef RTABMAP_ZED
00644                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00645 #else
00646                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00647 #endif
00648                                 str = "With RealSense:";
00649 #ifdef RTABMAP_REALSENSE
00650                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00651 #else
00652                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00653 #endif
00654                                 str = "With RealSense SLAM:";
00655 #ifdef RTABMAP_REALSENSE_SLAM
00656                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00657 #else
00658                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00659 #endif
00660                                 str = "With RealSense2:";
00661 #ifdef RTABMAP_REALSENSE2
00662                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00663 #else
00664                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00665 #endif
00666                                 str = "With libpointmatcher:";
00667 #ifdef RTABMAP_POINTMATCHER
00668                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00669 #else
00670                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00671 #endif
00672                                 str = "With octomap:";
00673 #ifdef RTABMAP_OCTOMAP
00674                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00675 #else
00676                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00677 #endif
00678                                 str = "With cpu-tsdf:";
00679 #ifdef RTABMAP_CPUTSDF
00680                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00681 #else
00682                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00683 #endif
00684                                 str = "With open chisel:";
00685 #ifdef RTABMAP_OPENCHISEL
00686                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00687 #else
00688                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00689 #endif
00690                                 str = "With LOAM:";
00691 #ifdef RTABMAP_LOAM
00692                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00693 #else
00694                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00695 #endif
00696                                 str = "With FOVIS:";
00697 #ifdef RTABMAP_FOVIS
00698                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00699 #else
00700                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00701 #endif
00702                                 str = "With Viso2:";
00703 #ifdef RTABMAP_VISO2
00704                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00705 #else
00706                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00707 #endif
00708                                 str = "With DVO:";
00709 #ifdef RTABMAP_DVO
00710                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00711 #else
00712                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00713 #endif
00714                                 str = "With ORB_SLAM2:";
00715 #ifdef RTABMAP_ORB_SLAM2
00716                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00717 #else
00718                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00719 #endif
00720                                 str = "With OKVIS:";
00721 #ifdef RTABMAP_OKVIS
00722                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00723 #else
00724                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00725 #endif
00726                                 str = "With MSCKF_VIO:";
00727 #ifdef RTABMAP_MSCKF_VIO
00728                                 std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
00729 #else
00730                                 std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
00731 #endif
00732                                 exit(0);
00733                         }
00734                         else if(strcmp(argv[i], "--nolog") == 0)
00735                         {
00736                                 ULogger::setType(ULogger::kTypeNoLog);
00737                         }
00738                         else if(strcmp(argv[i], "--logconsole") == 0)
00739                         {
00740                                 ULogger::setType(ULogger::kTypeConsole);
00741                         }
00742                         else if(strcmp(argv[i], "--logfile") == 0)
00743                         {
00744                                 ++i;
00745                                 if(i < argc)
00746                                 {
00747                                         ULogger::setType(ULogger::kTypeFile, argv[i], false);
00748                                 }
00749                                 else
00750                                 {
00751                                         UERROR("\"--logfile\" argument requires following file path");
00752                                 }
00753                         }
00754                         else if(strcmp(argv[i], "--logfilea") == 0)
00755                         {
00756                                 ++i;
00757                                 if(i < argc)
00758                                 {
00759                                         ULogger::setType(ULogger::kTypeFile, argv[i], true);
00760                                 }
00761                                 else
00762                                 {
00763                                         UERROR("\"--logfilea\" argument requires following file path");
00764                                 }
00765                         }
00766                         else if(strcmp(argv[i], "--udebug") == 0)
00767                         {
00768                                 ULogger::setLevel(ULogger::kDebug);
00769                         }
00770                         else if(strcmp(argv[i], "--uinfo") == 0)
00771                         {
00772                                 ULogger::setLevel(ULogger::kInfo);
00773                         }
00774                         else if(strcmp(argv[i], "--uwarn") == 0)
00775                         {
00776                                 ULogger::setLevel(ULogger::kWarning);
00777                         }
00778                         else if(strcmp(argv[i], "--uerror") == 0)
00779                         {
00780                                 ULogger::setLevel(ULogger::kError);
00781                         }
00782                         else if(strcmp(argv[i], "--ulogtime") == 0)
00783                         {
00784                                 ++i;
00785                                 if(i < argc)
00786                                 {
00787                                         ULogger::setPrintTime(uStr2Bool(argv[i]));
00788                                 }
00789                                 else
00790                                 {
00791                                         UERROR("\"--ulogtime\" argument requires a following boolean value");
00792                                 }
00793                         }
00794                         else if(strcmp(argv[i], "--ulogwhere") == 0)
00795                         {
00796                                 ++i;
00797                                 if(i < argc)
00798                                 {
00799                                         ULogger::setPrintWhere(uStr2Bool(argv[i]));
00800                                 }
00801                                 else
00802                                 {
00803                                         UERROR("\"--ulogwhere\" argument requires a following boolean value");
00804                                 }
00805                         }
00806                         else if(strcmp(argv[i], "--ulogthread") == 0)
00807                         {
00808                                 ++i;
00809                                 if(i < argc)
00810                                 {
00811                                         ULogger::setPrintThreadId(uStr2Bool(argv[i]));
00812                                 }
00813                                 else
00814                                 {
00815                                         UERROR("\"--ulogthread\" argument requires a following boolean value");
00816                                 }
00817                         }
00818                         else
00819                         {
00820                                 checkParameters = true;
00821                         }
00822                 }
00823 
00824                 if(checkParameters) // check for parameters
00825                 {
00826                         if(strcmp(argv[i], "--params") == 0)
00827                         {
00828                                 for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
00829                                 {
00830                                         bool ignore = false;
00831                                         UASSERT(uSplit(iter->first, '/').size()  == 2);
00832                                         std::string group = uSplit(iter->first, '/').front();
00833 #ifndef RTABMAP_GTSAM
00834                                    if(group.compare("GTSAM") == 0)
00835                                    {
00836                                            ignore = true;
00837                                    }
00838 #endif
00839 #ifndef RTABMAP_G2O
00840                                         if(group.compare("g2o") == 0)
00841                                         {
00842                                                 ignore = true;
00843                                         }
00844 #endif
00845 #ifndef RTABMAP_FOVIS
00846                                         if(group.compare("OdomFovis") == 0)
00847                                         {
00848                                                 ignore = true;
00849                                         }
00850 #endif
00851 #ifndef RTABMAP_VISO2
00852                                         if(group.compare("OdomViso2") == 0)
00853                                         {
00854                                                 ignore = true;
00855                                         }
00856 #endif
00857 #ifndef RTABMAP_ORBSLAM2
00858                                         if(group.compare("OdomORBSLAM2") == 0)
00859                                         {
00860                                                 ignore = true;
00861                                         }
00862 #endif
00863 #ifndef RTABMAP_OKVIS
00864                                         if(group.compare("OdomOKVIS") == 0)
00865                                         {
00866                                                 ignore = true;
00867                                         }
00868 #endif
00869 #ifndef RTABMAP_LOAM
00870                                         if(group.compare("OdomLOAM") == 0)
00871                                         {
00872                                                 ignore = true;
00873                                         }
00874 #endif
00875 #ifndef RTABMAP_MSCKF_VIO
00876                                         if(group.compare("OdomMSCKF") == 0)
00877                                         {
00878                                                 ignore = true;
00879                                         }
00880 #endif
00881                                         if(!ignore)
00882                                         {
00883                                                 std::string str = "Param: " + iter->first + " = \"" + iter->second + "\"";
00884                                                 std::cout <<
00885                                                                 str <<
00886                                                                 std::setw(60 - str.size()) <<
00887                                                                 " [" <<
00888                                                                 rtabmap::Parameters::getDescription(iter->first).c_str() <<
00889                                                                 "]" <<
00890                                                                 std::endl;
00891                                         }
00892                                 }
00893                                 UWARN("App will now exit after showing default RTAB-Map parameters because "
00894                                                  "argument \"--params\" is detected!");
00895                                 exit(0);
00896                         }
00897                         else
00898                         {
00899                                 std::string key = uReplaceChar(argv[i], '-', "");
00900                                 ParametersMap::const_iterator iter = parameters.find(key);
00901                                 if(iter != parameters.end())
00902                                 {
00903                                         ++i;
00904                                         if(i < argc)
00905                                         {
00906                                                 uInsert(out, ParametersPair(iter->first, argv[i]));
00907                                                 UINFO("Parsed parameter \"%s\"=\"%s\"", iter->first.c_str(), argv[i]);
00908                                         }
00909                                 }
00910                                 else
00911                                 {
00912                                         // backward compatibility
00913                                         std::map<std::string, std::pair<bool, std::string> >::const_iterator jter = removedParams.find(key);
00914                                         if(jter!=removedParams.end())
00915                                         {
00916                                                 if(jter->second.first)
00917                                                 {
00918                                                         ++i;
00919                                                         if(i < argc)
00920                                                         {
00921                                                                 std::string value = argv[i];
00922                                                                 if(!value.empty())
00923                                                                 {
00924                                                                         value = uReplaceChar(value, ',', ' '); // for table
00925                                                                         key = jter->second.second;
00926                                                                         UWARN("Parameter migration from \"%s\" to \"%s\" (value=%s).",
00927                                                                                         jter->first.c_str(), jter->second.second.c_str(), value.c_str());
00928                                                                         uInsert(out, ParametersPair(key, value));
00929                                                                 }
00930                                                         }
00931                                                         else
00932                                                         {
00933                                                                 UERROR("Value missing for argument \"%s\"", argv[i-1]);
00934                                                         }
00935                                                 }
00936                                                 else if(jter->second.second.empty())
00937                                                 {
00938                                                         UERROR("Parameter \"%s\" doesn't exist anymore.", jter->first.c_str());
00939                                                 }
00940                                                 else
00941                                                 {
00942                                                         UERROR("Parameter \"%s\" doesn't exist anymore, check this similar parameter \"%s\".", jter->first.c_str(), jter->second.second.c_str());
00943                                                 }
00944                                         }
00945                                 }
00946                         }
00947                 }
00948         }
00949         return out;
00950 }
00951 
00952 
00953 void Parameters::readINI(const std::string & configFile, ParametersMap & parameters, bool modifiedOnly)
00954 {
00955         CSimpleIniA ini;
00956         ini.LoadFile(configFile.c_str());
00957         const CSimpleIniA::TKeyVal * keyValMap = ini.GetSection("Core");
00958         if(keyValMap)
00959         {
00960                 for(CSimpleIniA::TKeyVal::const_iterator iter=keyValMap->begin(); iter!=keyValMap->end(); ++iter)
00961                 {
00962                         std::string key = (*iter).first.pItem;
00963                         if(key.compare("Version") == 0)
00964                         {
00965                                 // Compare version in ini with the current RTAB-Map version
00966                                 std::vector<std::string> version = uListToVector(uSplit((*iter).second, '.'));
00967                                 if(version.size() == 3)
00968                                 {
00969                                         if(!RTABMAP_VERSION_COMPARE(std::atoi(version[0].c_str()), std::atoi(version[1].c_str()), std::atoi(version[2].c_str())))
00970                                         {
00971                                                 if(configFile.find(".rtabmap") != std::string::npos)
00972                                                 {
00973                                                         UWARN("Version in the config file \"%s\" is more recent (\"%s\") than "
00974                                                                    "current RTAB-Map version used (\"%s\"). The config file will be upgraded "
00975                                                                    "to new version.",
00976                                                                    configFile.c_str(),
00977                                                                    (*iter).second,
00978                                                                    RTABMAP_VERSION);
00979                                                 }
00980                                                 else
00981                                                 {
00982                                                         UERROR("Version in the config file \"%s\" is more recent (\"%s\") than "
00983                                                                    "current RTAB-Map version used (\"%s\"). New parameters (if there are some) will "
00984                                                                    "be ignored.",
00985                                                                    configFile.c_str(),
00986                                                                    (*iter).second,
00987                                                                    RTABMAP_VERSION);
00988                                                 }
00989                                         }
00990                                 }
00991                         }
00992                         else
00993                         {
00994                                 key = uReplaceChar(key, '\\', '/'); // Ini files use \ by default for separators, so replace them
00995 
00996                                 // look for old parameter name
00997                                 std::map<std::string, std::pair<bool, std::string> >::const_iterator oldIter = Parameters::getRemovedParameters().find(key);
00998                                 if(oldIter!=Parameters::getRemovedParameters().end())
00999                                 {
01000                                         if(oldIter->second.first)
01001                                         {
01002                                                 if(parameters.find(oldIter->second.second) == parameters.end())
01003                                                 {
01004                                                         key = oldIter->second.second;
01005                                                         UINFO("Parameter migration from \"%s\" to \"%s\" (value=%s, default=%s).",
01006                                                                         oldIter->first.c_str(), oldIter->second.second.c_str(), iter->second, Parameters::getDefaultParameters().at(oldIter->second.second).c_str());
01007                                                 }
01008                                         }
01009                                         else if(oldIter->second.second.empty())
01010                                         {
01011                                                 UWARN("Parameter \"%s\" doesn't exist anymore.",
01012                                                                         oldIter->first.c_str());
01013                                         }
01014                                         else if(parameters.find(oldIter->second.second) == parameters.end())
01015                                         {
01016                                                 UWARN("Parameter \"%s\" (value=%s) doesn't exist anymore, you may want to use this similar parameter \"%s (default=%s): %s\".",
01017                                                                         oldIter->first.c_str(), iter->second, oldIter->second.second.c_str(), Parameters::getDefaultParameters().at(oldIter->second.second).c_str(), Parameters::getDescription(oldIter->second.second).c_str());
01018                                         }
01019 
01020                                 }
01021 
01022                                 if(Parameters::getDefaultParameters().find(key) != Parameters::getDefaultParameters().end())
01023                                 {
01024                                         if(!modifiedOnly || std::string(iter->second).compare(Parameters::getDefaultParameters().find(key)->second) != 0)
01025                                         {
01026                                                 uInsert(parameters, ParametersPair(key, iter->second));
01027                                         }
01028                                 }
01029                         }
01030                 }
01031         }
01032         else
01033         {
01034                 ULOGGER_WARN("Section \"Core\" in %s doesn't exist... "
01035                                     "Ignore this warning if the ini file does not exist yet. "
01036                                     "The ini file will be automatically created when rtabmap will close.", configFile.c_str());
01037         }
01038 }
01039 
01040 void Parameters::writeINI(const std::string & configFile, const ParametersMap & parameters)
01041 {
01042         CSimpleIniA ini;
01043         ini.LoadFile(configFile.c_str());
01044 
01045         // Save current version
01046         ini.SetValue("Core", "Version", RTABMAP_VERSION, NULL, true);
01047 
01048         for(ParametersMap::const_iterator i=parameters.begin(); i!=parameters.end(); ++i)
01049         {
01050                 std::string key = (*i).first;
01051                 key = uReplaceChar(key, '/', '\\'); // Ini files use \ by default for separators, so replace the /
01052                 
01053                 std::string value = (*i).second.c_str();
01054                 value = uReplaceChar(value, '\\', '/'); // use always slash for values
01055 
01056                 ini.SetValue("Core", key.c_str(), value.c_str(), NULL, true);
01057         }
01058 
01059         ini.SaveFile(configFile.c_str());
01060 }
01061 
01062 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:21