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(Parameters::getDefaultParameters().find(key) == Parameters::getDefaultParameters().end())
00140                         {
00141                                 UWARN("Unknown parameter \"%s\"=\"%s\"! The parameter is still added to output map.", key.c_str(), value.c_str());
00142                         }
00143                         uInsert(output, ParametersPair(key, value));
00144                 }
00145         }
00146         return output;
00147 }
00148 
00149 bool Parameters::isFeatureParameter(const std::string & parameter)
00150 {
00151         std::string group = uSplit(parameter, '/').front();
00152         return  group.compare("SURF") == 0 ||
00153                         group.compare("SIFT") == 0 ||
00154                         group.compare("ORB") == 0 ||
00155                         group.compare("FAST") == 0 ||
00156                         group.compare("FREAK") == 0 ||
00157                         group.compare("BRIEF") == 0 ||
00158                         group.compare("GFTT") == 0 ||
00159                         group.compare("BRISK") == 0;
00160 }
00161 
00162 rtabmap::ParametersMap Parameters::getDefaultOdometryParameters(bool stereo)
00163 {
00164         rtabmap::ParametersMap odomParameters;
00165         rtabmap::ParametersMap defaultParameters = rtabmap::Parameters::getDefaultParameters();
00166         for(rtabmap::ParametersMap::iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
00167         {
00168                 std::string group = uSplit(iter->first, '/').front();
00169                 if(uStrContains(group, "Odom") ||
00170                         (stereo && group.compare("Stereo") == 0) ||
00171                         Parameters::isFeatureParameter(iter->first) ||
00172                         group.compare("Reg") == 0 ||
00173                         group.compare("Vis") == 0)
00174                 {
00175                         if(stereo)
00176                         {
00177                                 if(iter->first.compare(Parameters::kVisEstimationType()) == 0)
00178                                 {
00179                                         iter->second = "1"; // 3D->2D (PNP)
00180                                 }
00181                         }
00182                         odomParameters.insert(*iter);
00183                 }
00184         }
00185         return odomParameters;
00186 }
00187 
00188 ParametersMap Parameters::getDefaultParameters(const std::string & group)
00189 {
00190         rtabmap::ParametersMap parameters;
00191         const rtabmap::ParametersMap & defaultParameters = rtabmap::Parameters::getDefaultParameters();
00192         for(rtabmap::ParametersMap::const_iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
00193         {
00194                 if(iter->first.compare(group) == 0)
00195                 {
00196                         parameters.insert(*iter);
00197                 }
00198         }
00199         UASSERT_MSG(parameters.size(), uFormat("No parameters found for group %s!", group.c_str()).c_str());
00200         return parameters;
00201 }
00202 
00203 ParametersMap Parameters::filterParameters(const ParametersMap & parameters, const std::string & group)
00204 {
00205         ParametersMap output;
00206         for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
00207         {
00208                 if(iter->first.compare(group) == 0)
00209                 {
00210                         output.insert(*iter);
00211                 }
00212         }
00213         return output;
00214 }
00215 
00216 const std::map<std::string, std::pair<bool, std::string> > & Parameters::getRemovedParameters()
00217 {
00218         if(removedParameters_.empty())
00219         {
00220                 // removed parameters
00221 
00222                 // 0.11.8
00223                 removedParameters_.insert(std::make_pair("Reg/Force2D",                   std::make_pair(true,  Parameters::kRegForce3DoF())));
00224                 removedParameters_.insert(std::make_pair("OdomF2M/ScanSubstractRadius",   std::make_pair(true,  Parameters::kOdomF2MScanSubtractRadius())));
00225 
00226                 // 0.11.6
00227                 removedParameters_.insert(std::make_pair("RGBD/ProximityPathScansMerged", std::make_pair(false,  "")));
00228 
00229                 // 0.11.3
00230                 removedParameters_.insert(std::make_pair("Mem/ImageDecimation",           std::make_pair(true, Parameters::kMemImagePostDecimation())));
00231 
00232                 // 0.11.2
00233                 removedParameters_.insert(std::make_pair("OdomLocalMap/HistorySize",      std::make_pair(true, Parameters::kOdomF2MMaxSize())));
00234                 removedParameters_.insert(std::make_pair("OdomLocalMap/FixedMapPath",     std::make_pair(true, Parameters::kOdomF2MFixedMapPath())));
00235                 removedParameters_.insert(std::make_pair("OdomF2F/GuessMotion",           std::make_pair(true, Parameters::kOdomGuessMotion())));
00236                 removedParameters_.insert(std::make_pair("OdomF2F/KeyFrameThr",           std::make_pair(false, Parameters::kOdomKeyFrameThr())));
00237 
00238                 // 0.11.0
00239                 removedParameters_.insert(std::make_pair("OdomBow/LocalHistorySize",      std::make_pair(true, Parameters::kOdomF2MMaxSize())));
00240                 removedParameters_.insert(std::make_pair("OdomBow/FixedLocalMapPath",     std::make_pair(true, Parameters::kOdomF2MFixedMapPath())));
00241                 removedParameters_.insert(std::make_pair("OdomFlow/KeyFrameThr",          std::make_pair(false, Parameters::kOdomKeyFrameThr())));
00242                 removedParameters_.insert(std::make_pair("OdomFlow/GuessMotion",          std::make_pair(true, Parameters::kOdomGuessMotion())));
00243 
00244                 removedParameters_.insert(std::make_pair("Kp/WordsPerImage",              std::make_pair(true, Parameters::kKpMaxFeatures())));
00245 
00246                 removedParameters_.insert(std::make_pair("Mem/LaserScanVoxelSize",        std::make_pair(false, Parameters::kMemLaserScanDownsampleStepSize())));
00247                 removedParameters_.insert(std::make_pair("Mem/LocalSpaceLinksKeptInWM",   std::make_pair(false, "")));
00248 
00249                 removedParameters_.insert(std::make_pair("RGBD/PoseScanMatching",         std::make_pair(true,  Parameters::kRGBDNeighborLinkRefining())));
00250 
00251                 removedParameters_.insert(std::make_pair("Odom/ParticleFiltering",        std::make_pair(false, Parameters::kOdomFilteringStrategy())));
00252                 removedParameters_.insert(std::make_pair("Odom/FeatureType",              std::make_pair(true,  Parameters::kVisFeatureType())));
00253                 removedParameters_.insert(std::make_pair("Odom/EstimationType",           std::make_pair(true,  Parameters::kVisEstimationType())));
00254                 removedParameters_.insert(std::make_pair("Odom/MaxFeatures",              std::make_pair(true,  Parameters::kVisMaxFeatures())));
00255                 removedParameters_.insert(std::make_pair("Odom/InlierDistance",           std::make_pair(true,  Parameters::kVisInlierDistance())));
00256                 removedParameters_.insert(std::make_pair("Odom/MinInliers",               std::make_pair(true,  Parameters::kVisMinInliers())));
00257                 removedParameters_.insert(std::make_pair("Odom/Iterations",               std::make_pair(true,  Parameters::kVisIterations())));
00258                 removedParameters_.insert(std::make_pair("Odom/RefineIterations",         std::make_pair(true,  Parameters::kVisRefineIterations())));
00259                 removedParameters_.insert(std::make_pair("Odom/MaxDepth",                 std::make_pair(true,  Parameters::kVisMaxDepth())));
00260                 removedParameters_.insert(std::make_pair("Odom/RoiRatios",                std::make_pair(true,  Parameters::kVisRoiRatios())));
00261                 removedParameters_.insert(std::make_pair("Odom/Force2D",                  std::make_pair(true,  Parameters::kRegForce3DoF())));
00262                 removedParameters_.insert(std::make_pair("Odom/VarianceFromInliersCount", std::make_pair(true,  Parameters::kRegVarianceFromInliersCount())));
00263                 removedParameters_.insert(std::make_pair("Odom/PnPReprojError",           std::make_pair(true,  Parameters::kVisPnPReprojError())));
00264                 removedParameters_.insert(std::make_pair("Odom/PnPFlags",                 std::make_pair(true,  Parameters::kVisPnPFlags())));
00265 
00266                 removedParameters_.insert(std::make_pair("OdomBow/NNType",                std::make_pair(true,  Parameters::kVisCorNNType())));
00267                 removedParameters_.insert(std::make_pair("OdomBow/NNDR",                  std::make_pair(true,  Parameters::kVisCorNNDR())));
00268 
00269                 removedParameters_.insert(std::make_pair("OdomFlow/WinSize",              std::make_pair(true,  Parameters::kVisCorFlowWinSize())));
00270                 removedParameters_.insert(std::make_pair("OdomFlow/Iterations",           std::make_pair(true,  Parameters::kVisCorFlowIterations())));
00271                 removedParameters_.insert(std::make_pair("OdomFlow/Eps",                  std::make_pair(true,  Parameters::kVisCorFlowEps())));
00272                 removedParameters_.insert(std::make_pair("OdomFlow/MaxLevel",             std::make_pair(true,  Parameters::kVisCorFlowMaxLevel())));
00273 
00274                 removedParameters_.insert(std::make_pair("OdomSubPix/WinSize",            std::make_pair(true,  Parameters::kVisSubPixWinSize())));
00275                 removedParameters_.insert(std::make_pair("OdomSubPix/Iterations",         std::make_pair(true,  Parameters::kVisSubPixIterations())));
00276                 removedParameters_.insert(std::make_pair("OdomSubPix/Eps",                std::make_pair(true,  Parameters::kVisSubPixEps())));
00277 
00278                 removedParameters_.insert(std::make_pair("LccReextract/Activated",         std::make_pair(true,   Parameters::kRGBDLoopClosureReextractFeatures())));
00279                 removedParameters_.insert(std::make_pair("LccReextract/FeatureType",       std::make_pair(false,  Parameters::kVisFeatureType())));
00280                 removedParameters_.insert(std::make_pair("LccReextract/MaxWords",          std::make_pair(false,  Parameters::kVisMaxFeatures())));
00281                 removedParameters_.insert(std::make_pair("LccReextract/MaxDepth",          std::make_pair(false,  Parameters::kVisMaxDepth())));
00282                 removedParameters_.insert(std::make_pair("LccReextract/RoiRatios",         std::make_pair(false,  Parameters::kVisRoiRatios())));
00283                 removedParameters_.insert(std::make_pair("LccReextract/NNType",            std::make_pair(false,  Parameters::kVisCorNNType())));
00284                 removedParameters_.insert(std::make_pair("LccReextract/NNDR",              std::make_pair(false,  Parameters::kVisCorNNDR())));
00285 
00286                 removedParameters_.insert(std::make_pair("LccBow/EstimationType",           std::make_pair(false,  Parameters::kVisEstimationType())));
00287                 removedParameters_.insert(std::make_pair("LccBow/InlierDistance",           std::make_pair(false,  Parameters::kVisInlierDistance())));
00288                 removedParameters_.insert(std::make_pair("LccBow/MinInliers",               std::make_pair(false,  Parameters::kVisMinInliers())));
00289                 removedParameters_.insert(std::make_pair("LccBow/Iterations",               std::make_pair(false,  Parameters::kVisIterations())));
00290                 removedParameters_.insert(std::make_pair("LccBow/RefineIterations",         std::make_pair(false,  Parameters::kVisRefineIterations())));
00291                 removedParameters_.insert(std::make_pair("LccBow/Force2D",                  std::make_pair(false,  Parameters::kRegForce3DoF())));
00292                 removedParameters_.insert(std::make_pair("LccBow/VarianceFromInliersCount", std::make_pair(false,  Parameters::kRegVarianceFromInliersCount())));
00293                 removedParameters_.insert(std::make_pair("LccBow/PnPReprojError",           std::make_pair(false,  Parameters::kVisPnPReprojError())));
00294                 removedParameters_.insert(std::make_pair("LccBow/PnPFlags",                 std::make_pair(false,  Parameters::kVisPnPFlags())));
00295                 removedParameters_.insert(std::make_pair("LccBow/EpipolarGeometryVar",      std::make_pair(true,   Parameters::kVisEpipolarGeometryVar())));
00296 
00297                 removedParameters_.insert(std::make_pair("LccIcp/Type",                         std::make_pair(false,  Parameters::kRegStrategy())));
00298 
00299                 removedParameters_.insert(std::make_pair("LccIcp3/Decimation",                  std::make_pair(false, "")));
00300                 removedParameters_.insert(std::make_pair("LccIcp3/MaxDepth",                    std::make_pair(false, "")));
00301                 removedParameters_.insert(std::make_pair("LccIcp3/VoxelSize",                   std::make_pair(false, Parameters::kIcpVoxelSize())));
00302                 removedParameters_.insert(std::make_pair("LccIcp3/Samples",                     std::make_pair(false, Parameters::kIcpDownsamplingStep())));
00303                 removedParameters_.insert(std::make_pair("LccIcp3/MaxCorrespondenceDistance",   std::make_pair(false, Parameters::kIcpMaxCorrespondenceDistance())));
00304                 removedParameters_.insert(std::make_pair("LccIcp3/Iterations",                  std::make_pair(false, Parameters::kIcpIterations())));
00305                 removedParameters_.insert(std::make_pair("LccIcp3/CorrespondenceRatio",         std::make_pair(false, Parameters::kIcpCorrespondenceRatio())));
00306                 removedParameters_.insert(std::make_pair("LccIcp3/PointToPlane",                std::make_pair(true,  Parameters::kIcpPointToPlane())));
00307                 removedParameters_.insert(std::make_pair("LccIcp3/PointToPlaneNormalNeighbors", std::make_pair(true,  Parameters::kIcpPointToPlaneNormalNeighbors())));
00308 
00309                 removedParameters_.insert(std::make_pair("LccIcp2/MaxCorrespondenceDistance",   std::make_pair(true,  Parameters::kIcpMaxCorrespondenceDistance())));
00310                 removedParameters_.insert(std::make_pair("LccIcp2/Iterations",                  std::make_pair(true,  Parameters::kIcpIterations())));
00311                 removedParameters_.insert(std::make_pair("LccIcp2/CorrespondenceRatio",         std::make_pair(true,  Parameters::kIcpCorrespondenceRatio())));
00312                 removedParameters_.insert(std::make_pair("LccIcp2/VoxelSize",                   std::make_pair(true,  Parameters::kIcpVoxelSize())));
00313 
00314                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionByTime",              std::make_pair(true,  Parameters::kRGBDProximityByTime())));
00315                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionBySpace",             std::make_pair(true,  Parameters::kRGBDProximityBySpace())));
00316                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionTime",                std::make_pair(true,  Parameters::kRGBDProximityByTime())));
00317                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionSpace",               std::make_pair(true,  Parameters::kRGBDProximityBySpace())));
00318                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathScansMerged",     std::make_pair(false,  "")));
00319                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxGraphDepth",       std::make_pair(true,  Parameters::kRGBDProximityMaxGraphDepth())));
00320                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathFilteringRadius", std::make_pair(true,  Parameters::kRGBDProximityPathFilteringRadius())));
00321                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathRawPosesUsed",    std::make_pair(true,  Parameters::kRGBDProximityPathRawPosesUsed())));
00322 
00323                 removedParameters_.insert(std::make_pair("RGBD/OptimizeStrategy",             std::make_pair(true,  Parameters::kOptimizerStrategy())));
00324                 removedParameters_.insert(std::make_pair("RGBD/OptimizeEpsilon",             std::make_pair(true,  Parameters::kOptimizerEpsilon())));
00325                 removedParameters_.insert(std::make_pair("RGBD/OptimizeIterations",          std::make_pair(true,  Parameters::kOptimizerIterations())));
00326                 removedParameters_.insert(std::make_pair("RGBD/OptimizeRobust",              std::make_pair(true,  Parameters::kOptimizerRobust())));
00327                 removedParameters_.insert(std::make_pair("RGBD/OptimizeSlam2D",              std::make_pair(true,  Parameters::kOptimizerSlam2D())));
00328                 removedParameters_.insert(std::make_pair("RGBD/OptimizeSlam2d",              std::make_pair(true,  Parameters::kOptimizerSlam2D())));
00329                 removedParameters_.insert(std::make_pair("RGBD/OptimizeVarianceIgnored",     std::make_pair(true,  Parameters::kOptimizerVarianceIgnored())));
00330 
00331                 removedParameters_.insert(std::make_pair("Stereo/WinSize",                   std::make_pair(true,  Parameters::kStereoWinWidth())));
00332 
00333                 // before 0.11.0
00334                 removedParameters_.insert(std::make_pair("GFTT/MaxCorners",                  std::make_pair(true, Parameters::kVisMaxFeatures())));
00335                 removedParameters_.insert(std::make_pair("LccBow/MaxDepth",                  std::make_pair(true, Parameters::kVisMaxDepth())));
00336                 removedParameters_.insert(std::make_pair("LccReextract/LoopClosureFeatures", std::make_pair(true, Parameters::kRGBDLoopClosureReextractFeatures())));
00337                 removedParameters_.insert(std::make_pair("Rtabmap/DetectorStrategy",         std::make_pair(true, Parameters::kKpDetectorStrategy())));
00338                 removedParameters_.insert(std::make_pair("RGBD/ScanMatchingSize",            std::make_pair(true, Parameters::kRGBDNeighborLinkRefining())));
00339                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionRadius",    std::make_pair(true, Parameters::kRGBDLocalRadius())));
00340                 removedParameters_.insert(std::make_pair("RGBD/ToroIterations",              std::make_pair(true, Parameters::kOptimizerIterations())));
00341                 removedParameters_.insert(std::make_pair("Mem/RehearsedNodesKept",           std::make_pair(true, Parameters::kMemNotLinkedNodesKept())));
00342                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(true, Parameters::kRGBDProximityMaxGraphDepth())));
00343                 removedParameters_.insert(std::make_pair("RGBD/PlanVirtualLinksMaxDiffID",   std::make_pair(false, "")));
00344                 removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(false, "")));
00345                 removedParameters_.insert(std::make_pair("Odom/Type",                        std::make_pair(true, Parameters::kVisFeatureType())));
00346                 removedParameters_.insert(std::make_pair("Odom/MaxWords",                    std::make_pair(true, Parameters::kVisMaxFeatures())));
00347                 removedParameters_.insert(std::make_pair("Odom/LocalHistory",                std::make_pair(true, Parameters::kOdomF2MMaxSize())));
00348                 removedParameters_.insert(std::make_pair("Odom/NearestNeighbor",             std::make_pair(true, Parameters::kVisCorNNType())));
00349                 removedParameters_.insert(std::make_pair("Odom/NNDR",                        std::make_pair(true, Parameters::kVisCorNNDR())));
00350         }
00351         return removedParameters_;
00352 }
00353 
00354 const ParametersMap & Parameters::getBackwardCompatibilityMap()
00355 {
00356         if(backwardCompatibilityMap_.empty())
00357         {
00358                 getRemovedParameters(); // make sure removedParameters is filled
00359 
00360                 // compatibility
00361                 for(std::map<std::string, std::pair<bool, std::string> >::iterator iter=removedParameters_.begin();
00362                         iter!=removedParameters_.end();
00363                         ++iter)
00364                 {
00365                         if(iter->second.first)
00366                         {
00367                                 backwardCompatibilityMap_.insert(ParametersPair(iter->second.second, iter->first));
00368                         }
00369                 }
00370         }
00371         return backwardCompatibilityMap_;
00372 }
00373 
00374 std::string Parameters::getType(const std::string & paramKey)
00375 {
00376         std::string type;
00377         ParametersMap::iterator iter = parametersType_.find(paramKey);
00378         if(iter != parametersType_.end())
00379         {
00380                 type = iter->second;
00381         }
00382         else
00383         {
00384                 UERROR("Parameters \"%s\" doesn't exist!", paramKey.c_str());
00385         }
00386         return type;
00387 }
00388 
00389 std::string Parameters::getDescription(const std::string & paramKey)
00390 {
00391         std::string description;
00392         ParametersMap::iterator iter = descriptions_.find(paramKey);
00393         if(iter != descriptions_.end())
00394         {
00395                 description = iter->second;
00396         }
00397         else
00398         {
00399                 UERROR("Parameters \"%s\" doesn't exist!", paramKey.c_str());
00400         }
00401         return description;
00402 }
00403 
00404 void Parameters::parse(const ParametersMap & parameters, const std::string & key, bool & value)
00405 {
00406         ParametersMap::const_iterator iter = parameters.find(key);
00407         if(iter != parameters.end())
00408         {
00409                 value = uStr2Bool(iter->second.c_str());
00410         }
00411 }
00412 void Parameters::parse(const ParametersMap & parameters, const std::string & key, int & value)
00413 {
00414         ParametersMap::const_iterator iter = parameters.find(key);
00415         if(iter != parameters.end())
00416         {
00417                 value = uStr2Int(iter->second.c_str());
00418         }
00419 }
00420 void Parameters::parse(const ParametersMap & parameters, const std::string & key, unsigned int & value)
00421 {
00422         ParametersMap::const_iterator iter = parameters.find(key);
00423         if(iter != parameters.end())
00424         {
00425                 value = uStr2Int(iter->second.c_str());
00426         }
00427 }
00428 void Parameters::parse(const ParametersMap & parameters, const std::string & key, float & value)
00429 {
00430         ParametersMap::const_iterator iter = parameters.find(key);
00431         if(iter != parameters.end())
00432         {
00433                 value = uStr2Float(iter->second);
00434         }
00435 }
00436 void Parameters::parse(const ParametersMap & parameters, const std::string & key, double & value)
00437 {
00438         ParametersMap::const_iterator iter = parameters.find(key);
00439         if(iter != parameters.end())
00440         {
00441                 value = uStr2Double(iter->second);
00442         }
00443 }
00444 void Parameters::parse(const ParametersMap & parameters, const std::string & key, std::string & value)
00445 {
00446         ParametersMap::const_iterator iter = parameters.find(key);
00447         if(iter != parameters.end())
00448         {
00449                 value = iter->second;
00450         }
00451 }
00452 void Parameters::parse(const ParametersMap & parameters, ParametersMap & parametersOut)
00453 {
00454         for(ParametersMap::iterator iter=parametersOut.begin(); iter!=parametersOut.end(); ++iter)
00455         {
00456                 ParametersMap::const_iterator jter = parameters.find(iter->first);
00457                 if(jter != parameters.end())
00458                 {
00459                         iter->second = jter->second;
00460                 }
00461         }
00462 }
00463 
00464 const char * Parameters::showUsage()
00465 {
00466         return  "Logger options:\n"
00467                         "   --nolog              Disable logger\n"
00468                         "   --logconsole         Set logger console type\n"
00469                         "   --logfile \"path\"     Set logger file type\n"
00470                         "   --logfilea \"path\"    Set logger file type with appending mode if the file already exists\n"
00471                         "   --udebug             Set logger level to debug\n"
00472                         "   --uinfo              Set logger level to info\n"
00473                         "   --uwarn              Set logger level to warn\n"
00474                         "   --uerror             Set logger level to error\n"
00475                         "   --logtime \"bool\"     Print time when logging\n"
00476                         "   --logwhere \"bool\"    Print where when logging\n"
00477                         "   --logthread \"bool\"   Print thread id when logging\n"
00478                         "RTAB-Map options:\n"
00479                         "   --params                       Show all parameters with their default value and description\n"
00480                         "   --\"parameter name\" \"value\"     Overwrite a specific RTAB-Map's parameter :\n"
00481                         "                                    --SURF/HessianThreshold 150\n"
00482                         "                                   For parameters in table format, add ',' between values :\n"
00483                         "                                    --Kp/RoiRatios 0,0,0.1,0\n"
00484                         ;
00485 }
00486 
00487 ParametersMap Parameters::parseArguments(int argc, char * argv[])
00488 {
00489         ParametersMap out;
00490         const ParametersMap & parameters = getDefaultParameters();
00491         const std::map<std::string, std::pair<bool, std::string> > & removedParams = getRemovedParameters();
00492         for(int i=0;i<argc;++i)
00493         {
00494                 if(strcmp(argv[i], "--nolog") == 0)
00495                 {
00496                         ULogger::setType(ULogger::kTypeNoLog);
00497                 }
00498                 else if(strcmp(argv[i], "--logconsole") == 0)
00499                 {
00500                         ULogger::setType(ULogger::kTypeConsole);
00501                 }
00502                 else if(strcmp(argv[i], "--logfile") == 0)
00503                 {
00504                         ++i;
00505                         if(i < argc)
00506                         {
00507                                 ULogger::setType(ULogger::kTypeFile, argv[i], false);
00508                         }
00509                         else
00510                         {
00511                                 UERROR("\"--logfile\" argument requires following file path");
00512                         }
00513                 }
00514                 else if(strcmp(argv[i], "--logfilea") == 0)
00515                 {
00516                         ++i;
00517                         if(i < argc)
00518                         {
00519                                 ULogger::setType(ULogger::kTypeFile, argv[i], true);
00520                         }
00521                         else
00522                         {
00523                                 UERROR("\"--logfilea\" argument requires following file path");
00524                         }
00525                 }
00526                 else if(strcmp(argv[i], "--udebug") == 0)
00527                 {
00528                         ULogger::setLevel(ULogger::kDebug);
00529                 }
00530                 else if(strcmp(argv[i], "--uinfo") == 0)
00531                 {
00532                         ULogger::setLevel(ULogger::kInfo);
00533                 }
00534                 else if(strcmp(argv[i], "--uwarn") == 0)
00535                 {
00536                         ULogger::setLevel(ULogger::kWarning);
00537                 }
00538                 else if(strcmp(argv[i], "--uerror") == 0)
00539                 {
00540                         ULogger::setLevel(ULogger::kError);
00541                 }
00542                 else if(strcmp(argv[i], "--ulogtime") == 0)
00543                 {
00544                         ++i;
00545                         if(i < argc)
00546                         {
00547                                 ULogger::setPrintTime(uStr2Bool(argv[i]));
00548                         }
00549                         else
00550                         {
00551                                 UERROR("\"--ulogtime\" argument requires a following boolean value");
00552                         }
00553                 }
00554                 else if(strcmp(argv[i], "--ulogwhere") == 0)
00555                 {
00556                         ++i;
00557                         if(i < argc)
00558                         {
00559                                 ULogger::setPrintWhere(uStr2Bool(argv[i]));
00560                         }
00561                         else
00562                         {
00563                                 UERROR("\"--ulogwhere\" argument requires a following boolean value");
00564                         }
00565                 }
00566                 else if(strcmp(argv[i], "--ulogthread") == 0)
00567                 {
00568                         ++i;
00569                         if(i < argc)
00570                         {
00571                                 ULogger::setPrintThreadId(uStr2Bool(argv[i]));
00572                         }
00573                         else
00574                         {
00575                                 UERROR("\"--ulogthread\" argument requires a following boolean value");
00576                         }
00577                 }
00578                 else if(strcmp(argv[i], "--params") == 0)
00579                 {
00580                         for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
00581                         {
00582                                 std::string str = "Param: " + iter->first + " = \"" + iter->second + "\"";
00583                                 std::cout <<
00584                                                 str <<
00585                                                 std::setw(60 - str.size()) <<
00586                                                 " [" <<
00587                                                 rtabmap::Parameters::getDescription(iter->first).c_str() <<
00588                                                 "]" <<
00589                                                 std::endl;
00590                         }
00591                         UWARN("App will now exit after showing default RTAB-Map parameters because "
00592                                          "argument \"--params\" is detected!");
00593                         exit(0);
00594                 }
00595                 else // check for parameters
00596                 {
00597                         std::string key = uReplaceChar(argv[i], '-', "");
00598                         ParametersMap::const_iterator iter = parameters.find(key);
00599                         if(iter != parameters.end())
00600                         {
00601                                 ++i;
00602                                 if(i < argc)
00603                                 {
00604                                         uInsert(out, ParametersPair(iter->first, argv[i]));
00605                                 }
00606                         }
00607                         else
00608                         {
00609                                 // backward compatibility
00610                                 std::map<std::string, std::pair<bool, std::string> >::const_iterator jter = removedParams.find(key);
00611                                 if(jter!=removedParams.end())
00612                                 {
00613                                         if(jter->second.first)
00614                                         {
00615                                                 ++i;
00616                                                 if(i < argc)
00617                                                 {
00618                                                         std::string value = argv[i];
00619                                                         if(!value.empty())
00620                                                         {
00621                                                                 value = uReplaceChar(value, ',', ' '); // for table
00622                                                                 key = jter->second.second;
00623                                                                 UWARN("Parameter migration from \"%s\" to \"%s\" (value=%s).",
00624                                                                                 jter->first.c_str(), jter->second.second.c_str(), value.c_str());
00625                                                                 uInsert(out, ParametersPair(key, value));
00626                                                         }
00627                                                 }
00628                                                 else
00629                                                 {
00630                                                         UERROR("Value missing for argument \"%s\"", argv[i-1]);
00631                                                 }
00632                                         }
00633                                         else if(jter->second.second.empty())
00634                                         {
00635                                                 UERROR("Parameter \"%s\" doesn't exist anymore.", jter->first.c_str());
00636                                         }
00637                                         else
00638                                         {
00639                                                 UERROR("Parameter \"%s\" doesn't exist anymore, check this similar parameter \"%s\".", jter->first.c_str(), jter->second.second.c_str());
00640                                         }
00641                                 }
00642                         }
00643                 }
00644         }
00645         return out;
00646 }
00647 
00648 
00649 void Parameters::readINI(const std::string & configFile, ParametersMap & parameters)
00650 {
00651         CSimpleIniA ini;
00652         ini.LoadFile(configFile.c_str());
00653         const CSimpleIniA::TKeyVal * keyValMap = ini.GetSection("Core");
00654         if(keyValMap)
00655         {
00656                 for(CSimpleIniA::TKeyVal::const_iterator iter=keyValMap->begin(); iter!=keyValMap->end(); ++iter)
00657                 {
00658                         std::string key = (*iter).first.pItem;
00659                         if(key.compare("Version") == 0)
00660                         {
00661                                 // Compare version in ini with the current RTAB-Map version
00662                                 std::vector<std::string> version = uListToVector(uSplit((*iter).second, '.'));
00663                                 if(version.size() == 3)
00664                                 {
00665                                         if(!RTABMAP_VERSION_COMPARE(std::atoi(version[0].c_str()), std::atoi(version[1].c_str()), std::atoi(version[2].c_str())))
00666                                         {
00667                                                 if(configFile.find(".rtabmap") != std::string::npos)
00668                                                 {
00669                                                         UWARN("Version in the config file \"%s\" is more recent (\"%s\") than "
00670                                                                    "current RTAB-Map version used (\"%s\"). The config file will be upgraded "
00671                                                                    "to new version.",
00672                                                                    configFile.c_str(),
00673                                                                    (*iter).second,
00674                                                                    RTABMAP_VERSION);
00675                                                 }
00676                                                 else
00677                                                 {
00678                                                         UERROR("Version in the config file \"%s\" is more recent (\"%s\") than "
00679                                                                    "current RTAB-Map version used (\"%s\"). New parameters (if there are some) will "
00680                                                                    "be ignored.",
00681                                                                    configFile.c_str(),
00682                                                                    (*iter).second,
00683                                                                    RTABMAP_VERSION);
00684                                                 }
00685                                         }
00686                                 }
00687                         }
00688                         else
00689                         {
00690                                 key = uReplaceChar(key, '\\', '/'); // Ini files use \ by default for separators, so replace them
00691 
00692                                 // look for old parameter name
00693                                 bool addParameter = true;
00694                                 std::map<std::string, std::pair<bool, std::string> >::const_iterator oldIter = Parameters::getRemovedParameters().find(key);
00695                                 if(oldIter!=Parameters::getRemovedParameters().end())
00696                                 {
00697                                         addParameter = oldIter->second.first;
00698                                         if(addParameter)
00699                                         {
00700                                                 key = oldIter->second.second;
00701                                                 UWARN("Parameter migration from \"%s\" to \"%s\" (value=%s).",
00702                                                                 oldIter->first.c_str(), oldIter->second.second.c_str(), iter->second);
00703                                         }
00704                                         else if(oldIter->second.second.empty())
00705                                         {
00706                                                 UWARN("Parameter \"%s\" doesn't exist anymore.",
00707                                                                         oldIter->first.c_str());
00708                                         }
00709                                         else
00710                                         {
00711                                                 UWARN("Parameter \"%s\" doesn't exist anymore, you may want to use this similar parameter \"%s\":\"%s\".",
00712                                                                         oldIter->first.c_str(), oldIter->second.second.c_str(), Parameters::getDescription(oldIter->second.second).c_str());
00713                                         }
00714 
00715                                 }
00716 
00717                                 if(Parameters::getDefaultParameters().find(key) != Parameters::getDefaultParameters().end())
00718                                 {
00719                                         uInsert(parameters, ParametersPair(key, iter->second));
00720                                 }
00721                         }
00722                 }
00723         }
00724         else
00725         {
00726                 ULOGGER_WARN("Section \"Core\" in %s doesn't exist... "
00727                                     "Ignore this warning if the ini file does not exist yet. "
00728                                     "The ini file will be automatically created when this node will close.", configFile.c_str());
00729         }
00730 }
00731 
00732 void Parameters::writeINI(const std::string & configFile, const ParametersMap & parameters)
00733 {
00734         CSimpleIniA ini;
00735         ini.LoadFile(configFile.c_str());
00736 
00737         // Save current version
00738         ini.SetValue("Core", "Version", RTABMAP_VERSION, NULL, true);
00739 
00740         for(ParametersMap::const_iterator i=parameters.begin(); i!=parameters.end(); ++i)
00741         {
00742                 std::string key = (*i).first;
00743                 key = uReplaceChar(key, '/', '\\'); // Ini files use \ by default for separators, so replace the /
00744                 ini.SetValue("Core", key.c_str(), (*i).second.c_str(), NULL, true);
00745         }
00746 
00747         ini.SaveFile(configFile.c_str());
00748 }
00749 
00750 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:17