Recovery.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2017, 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/Recovery.h>
00029 #include <rtabmap/core/Rtabmap.h>
00030 #include <rtabmap/core/DBDriver.h>
00031 #include <rtabmap/core/DBReader.h>
00032 #include <rtabmap/core/Graph.h>
00033 #include <rtabmap/core/ProgressState.h>
00034 #include <rtabmap/utilite/UFile.h>
00035 #include <rtabmap/utilite/UStl.h>
00036 
00037 namespace rtabmap {
00038 
00039 bool databaseRecovery(
00040                 const std::string & corruptedDatabase,
00041                 bool keepCorruptedDatabase,
00042                 std::string * errorMsg,
00043                 ProgressState * progressState)
00044 {
00045         UDEBUG("Recovering \"%s\"", corruptedDatabase.c_str());
00046 
00047         std::string databasePath = uReplaceChar(corruptedDatabase, '~', UDirectory::homeDir());
00048         if(!UFile::exists(databasePath))
00049         {
00050                 if(errorMsg)
00051                         *errorMsg = uFormat("File \"%s\" doesn't exist!", databasePath.c_str());
00052                 return false;
00053         }
00054 
00055         std::string backupPath;
00056         if(UFile::getExtension(databasePath).compare("db") != 0)
00057         {
00058                 if(errorMsg)
00059                         *errorMsg = uFormat("File \"%s\" is not a database (*.db)!", databasePath.c_str());
00060                 return false;
00061         }
00062         std::list<std::string> strList = uSplit(databasePath, '.');
00063         strList.pop_back();
00064         backupPath = uJoin(strList, ".") + ".backup.db";
00065         if(UFile::exists(backupPath))
00066         {
00067                 if(errorMsg)
00068                         *errorMsg = uFormat("Backup file \"%s\" already exists!", backupPath.c_str());
00069                 return false;
00070         }
00071 
00072         DBDriver * dbDriver = DBDriver::create();
00073         if(!dbDriver->openConnection(databasePath, false))
00074         {
00075                 if(errorMsg)
00076                         *errorMsg = uFormat("Failed opening database!");
00077                 delete dbDriver;
00078                 return false;
00079         }
00080 
00081         ParametersMap parameters = dbDriver->getLastParameters();
00082         if(parameters.empty())
00083         {
00084                 if(errorMsg)
00085                         *errorMsg = uFormat("Failed getting parameters from database, recovery cannot be done.");
00086                 dbDriver->closeConnection(false);
00087                 delete dbDriver;
00088                 return false;
00089         }
00090         std::set<int> ids;
00091         dbDriver->getAllNodeIds(ids);
00092         if(ids.empty())
00093         {
00094                 if(errorMsg)
00095                         *errorMsg = uFormat("Input database doesn't have any nodes saved in it.");
00096                 dbDriver->closeConnection(false);
00097                 delete dbDriver;
00098                 return false;
00099         }
00100         if(progressState)
00101                 progressState->callback(uFormat("Found %d nodes to recover.", (int)ids.size()));
00102 
00103         //Detect if the database is corrupted
00104         std::multimap<int, Link> links;
00105         dbDriver->getAllLinks(links, true);
00106         bool corrupted = false;
00107         for(std::multimap<int, Link>::iterator iter=links.begin(); iter!=links.end(); ++iter)
00108         {
00109                 if(iter->second.type() == Link::kNeighbor &&
00110                         graph::findLink(links, iter->second.to(), iter->second.from(), false) == links.end())
00111                 {
00112                         corrupted = true;
00113                         break;
00114                 }
00115         }
00116 
00117         if(progressState)
00118         {
00119                 if(corrupted)
00120                         progressState->callback("Database is indeed corrupted, found one or more neighbor links missing.");
00121                 else
00122                         progressState->callback("Database doesn't seem to be corrupted, still recovering it.");
00123         }
00124 
00125         dbDriver->closeConnection(false);
00126         delete dbDriver;
00127 
00128         if(progressState)
00129                 progressState->callback(uFormat("Renaming \"%s\" to \"%s\"...", UFile::getName(databasePath).c_str(), UFile::getName(backupPath).c_str()));
00130         if(UFile::rename(databasePath, backupPath) != 0)
00131         {
00132                 if(errorMsg)
00133                         *errorMsg = uFormat("Failed renaming database file from \"%s\" to \"%s\". Is it opened by another app?", UFile::getName(databasePath).c_str(), UFile::getName(backupPath).c_str());
00134                 return false;
00135         }
00136         Rtabmap rtabmap;
00137         rtabmap.init(parameters, databasePath);
00138 
00139         bool rgbdEnabled = Parameters::defaultRGBDEnabled();
00140         Parameters::parse(parameters, Parameters::kRGBDEnabled(), rgbdEnabled);
00141         bool odometryIgnored = !rgbdEnabled;
00142         DBReader dbReader(backupPath, 0, odometryIgnored);
00143         dbReader.init();
00144 
00145         CameraInfo info;
00146         SensorData data = dbReader.takeImage(&info);
00147         int processed = 0;
00148         if(progressState)
00149                 progressState->callback(uFormat("Recovering data of \"%s\"...", backupPath.c_str()));
00150         while(data.isValid() && (progressState==0 || !progressState->isCanceled()))
00151         {
00152                 std::string status;
00153                 if(!odometryIgnored && info.odomPose.isNull())
00154                 {
00155                         status = uFormat("Skipping node %d as it doesn't have odometry pose set.", data.id());
00156                 }
00157                 else
00158                 {
00159                         if(!odometryIgnored && !info.odomCovariance.empty() && info.odomCovariance.at<double>(0,0)>=9999)
00160                         {
00161                                 status = uFormat("High variance detected, triggering a new map...");
00162                                 rtabmap.triggerNewMap();
00163                         }
00164                         if(!rtabmap.process(data, info.odomPose, info.odomCovariance, info.odomVelocity))
00165                         {
00166                                 status = uFormat("Failed processing node %d.", data.id());
00167                         }
00168                 }
00169                 if(status.empty())
00170                 {
00171                         if(progressState)
00172                                 progressState->callback(status);
00173                 }
00174 
00175                 data = dbReader.takeImage(&info);
00176 
00177                 if(progressState)
00178                         progressState->callback(uFormat("Processed %d/%d nodes...", ++processed, (int)ids.size()));
00179         }
00180 
00181         if(progressState)
00182         {
00183                 if(progressState->isCanceled())
00184                 {
00185                         rtabmap.close(false);
00186                         if(errorMsg)
00187                                 *errorMsg = uFormat("Recovery canceled, renaming back \"%s\" to \"%s\".", backupPath.c_str(), databasePath.c_str());
00188 
00189                         // put back the file as before
00190                         UFile::erase(databasePath);
00191                         UFile::rename(backupPath, databasePath);
00192                         return false;
00193                 }
00194         }
00195 
00196         if(progressState)
00197                 progressState->callback(uFormat("Closing database \"%s\"...", databasePath.c_str()));
00198         rtabmap.close(true);
00199         if(progressState)
00200                 progressState->callback(uFormat("Closing database \"%s\"... done!", databasePath.c_str()));
00201 
00202         if(!keepCorruptedDatabase)
00203         {
00204                 UFile::erase(backupPath);
00205         }
00206 
00207         return true;
00208 }
00209 
00210 }
00211 
00212 
00213 
00214 


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