OptimizerTORO.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 #include "rtabmap/core/Graph.h"
00028 
00029 #include <rtabmap/utilite/ULogger.h>
00030 #include <rtabmap/utilite/UStl.h>
00031 #include <rtabmap/utilite/UMath.h>
00032 #include <rtabmap/utilite/UConversion.h>
00033 #include <rtabmap/utilite/UTimer.h>
00034 #include <set>
00035 
00036 #include <rtabmap/core/OptimizerTORO.h>
00037 
00038 #ifdef RTABMAP_TORO
00039 #include "toro3d/treeoptimizer3.hh"
00040 #include "toro3d/treeoptimizer2.hh"
00041 #endif
00042 
00043 namespace rtabmap {
00044 
00045 bool OptimizerTORO::available()
00046 {
00047 #ifdef RTABMAP_TORO
00048         return true;
00049 #else
00050         return false;
00051 #endif
00052 }
00053 
00054 std::map<int, Transform> OptimizerTORO::optimize(
00055                 int rootId,
00056                 const std::map<int, Transform> & poses,
00057                 const std::multimap<int, Link> & edgeConstraints,
00058                 std::list<std::map<int, Transform> > * intermediateGraphes, // contains poses after tree init to last one before the end
00059                 double * finalError,
00060                 int * iterationsDone)
00061 {
00062         std::map<int, Transform> optimizedPoses;
00063 #ifdef RTABMAP_TORO
00064         UDEBUG("Optimizing graph (pose=%d constraints=%d)...", (int)poses.size(), (int)edgeConstraints.size());
00065         if(edgeConstraints.size()>=1 && poses.size()>=2 && iterations() > 0)
00066         {
00067                 // Apply TORO optimization
00068                 AISNavigation::TreeOptimizer2 pg2;
00069                 AISNavigation::TreeOptimizer3 pg3;
00070                 pg2.verboseLevel = 0;
00071                 pg3.verboseLevel = 0;
00072 
00073                 UDEBUG("fill poses to TORO...");
00074                 if(isSlam2d())
00075                 {
00076                         for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end(); ++iter)
00077                         {
00078                                 UASSERT(!iter->second.isNull());
00079                                 AISNavigation::TreePoseGraph2::Pose p(iter->second.x(), iter->second.y(), iter->second.theta());
00080                                 AISNavigation::TreePoseGraph2::Vertex* v = pg2.addVertex(iter->first, p);
00081                                 UASSERT_MSG(v != 0, uFormat("cannot insert vertex %d!?", iter->first).c_str());
00082                         }
00083                 }
00084                 else
00085                 {
00086                         for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end(); ++iter)
00087                         {
00088                                 UASSERT(!iter->second.isNull());
00089                                 float x,y,z, roll,pitch,yaw;
00090                                 iter->second.getTranslationAndEulerAngles(x,y,z, roll,pitch,yaw);
00091                                 AISNavigation::TreePoseGraph3::Pose p(x, y, z, roll, pitch, yaw);
00092                                 AISNavigation::TreePoseGraph3::Vertex* v = pg3.addVertex(iter->first, p);
00093                                 UASSERT_MSG(v != 0, uFormat("cannot insert vertex %d!?", iter->first).c_str());
00094                                 v->transformation=AISNavigation::TreePoseGraph3::Transformation(p);
00095                         }
00096 
00097                 }
00098 
00099                 UDEBUG("fill edges to TORO...");
00100                 if(isSlam2d())
00101                 {
00102                         for(std::multimap<int, Link>::const_iterator iter=edgeConstraints.begin(); iter!=edgeConstraints.end(); ++iter)
00103                         {
00104                                 UASSERT(!iter->second.transform().isNull());
00105                                 AISNavigation::TreePoseGraph2::Pose p(iter->second.transform().x(), iter->second.transform().y(), iter->second.transform().theta());
00106                                 AISNavigation::TreePoseGraph2::InformationMatrix inf;
00107                                 //Identity:
00108                                 if(isCovarianceIgnored())
00109                                 {
00110                                         inf.values[0][0] = 1.0; inf.values[0][1] = 0.0; inf.values[0][2] = 0.0; // x
00111                                         inf.values[1][0] = 0.0; inf.values[1][1] = 1.0; inf.values[1][2] = 0.0; // y
00112                                         inf.values[2][0] = 0.0; inf.values[2][1] = 0.0; inf.values[2][2] = 1.0; // theta/yaw
00113                                 }
00114                                 else
00115                                 {
00116                                         inf.values[0][0] = iter->second.infMatrix().at<double>(0,0); // x-x
00117                                         inf.values[0][1] = iter->second.infMatrix().at<double>(0,1); // x-y
00118                                         inf.values[0][2] = iter->second.infMatrix().at<double>(0,5); // x-theta
00119                                         inf.values[1][0] = iter->second.infMatrix().at<double>(1,0); // y-x
00120                                         inf.values[1][1] = iter->second.infMatrix().at<double>(1,1); // y-y
00121                                         inf.values[1][2] = iter->second.infMatrix().at<double>(1,5); // y-theta
00122                                         inf.values[2][0] = iter->second.infMatrix().at<double>(5,0); // theta-x
00123                                         inf.values[2][1] = iter->second.infMatrix().at<double>(5,1); // theta-y
00124                                         inf.values[2][2] = iter->second.infMatrix().at<double>(5,5); // theta-theta
00125                                 }
00126 
00127                                 int id1 = iter->first;
00128                                 int id2 = iter->second.to();
00129                                 AISNavigation::TreePoseGraph2::Vertex* v1=pg2.vertex(id1);
00130                                 AISNavigation::TreePoseGraph2::Vertex* v2=pg2.vertex(id2);
00131                                 UASSERT(v1 != 0);
00132                                 UASSERT(v2 != 0);
00133                                 AISNavigation::TreePoseGraph2::Transformation t(p);
00134                                 if (!pg2.addEdge(v1, v2, t, inf))
00135                                 {
00136                                         UERROR("Map: Edge already exits between nodes %d and %d, skipping", id1, id2);
00137                                 }
00138                         }
00139                 }
00140                 else
00141                 {
00142                         for(std::multimap<int, Link>::const_iterator iter=edgeConstraints.begin(); iter!=edgeConstraints.end(); ++iter)
00143                         {
00144                                 UASSERT(!iter->second.transform().isNull());
00145                                 float x,y,z, roll,pitch,yaw;
00146                                 iter->second.transform().getTranslationAndEulerAngles(x,y,z, roll,pitch,yaw);
00147 
00148                                 AISNavigation::TreePoseGraph3::Pose p(x, y, z, roll, pitch, yaw);
00149                                 AISNavigation::TreePoseGraph3::InformationMatrix inf = DMatrix<double>::I(6);
00150                                 if(!isCovarianceIgnored())
00151                                 {
00152                                         memcpy(inf[0], iter->second.infMatrix().data, iter->second.infMatrix().total()*sizeof(double));
00153                                 }
00154 
00155                                 int id1 = iter->first;
00156                                 int id2 = iter->second.to();
00157                                 AISNavigation::TreePoseGraph3::Vertex* v1=pg3.vertex(id1);
00158                                 AISNavigation::TreePoseGraph3::Vertex* v2=pg3.vertex(id2);
00159                                 UASSERT(v1 != 0);
00160                                 UASSERT(v2 != 0);
00161                                 AISNavigation::TreePoseGraph3::Transformation t(p);
00162                                 if (!pg3.addEdge(v1, v2, t, inf))
00163                                 {
00164                                         UERROR("Map: Edge already exits between nodes %d and %d, skipping", id1, id2);
00165                                 }
00166                         }
00167                 }
00168                 UDEBUG("buildMST... root=%d", rootId);
00169                 UASSERT(uContains(poses, rootId));
00170                 if(isSlam2d())
00171                 {
00172                         pg2.buildMST(rootId); // pg.buildSimpleTree();
00173                         //UDEBUG("initializeOnTree()");
00174                         //pg2.initializeOnTree();
00175                         UDEBUG("initializeTreeParameters()");
00176                         pg2.initializeTreeParameters();
00177                         UDEBUG("Building TORO tree... (if a crash happens just after this msg, "
00178                                    "TORO is not able to find the root of the graph!)");
00179                         pg2.initializeOptimization();
00180                 }
00181                 else
00182                 {
00183                         pg3.buildMST(rootId); // pg.buildSimpleTree();
00184                         //UDEBUG("initializeOnTree()");
00185                         //pg3.initializeOnTree();
00186                         UDEBUG("initializeTreeParameters()");
00187                         pg3.initializeTreeParameters();
00188                         UDEBUG("Building TORO tree... (if a crash happens just after this msg, "
00189                                    "TORO is not able to find the root of the graph!)");
00190                         pg3.initializeOptimization();
00191                 }
00192 
00193                 UINFO("Initial error = %f", pg2.error());
00194                 UINFO("TORO optimizing begin (iterations=%d)", iterations());
00195                 double lastError = 0;
00196                 int i=0;
00197                 UTimer timer;
00198                 for (; i<iterations(); i++)
00199                 {
00200                         if(intermediateGraphes && i>0)
00201                         {
00202                                 std::map<int, Transform> tmpPoses;
00203                                 if(isSlam2d())
00204                                 {
00205                                         for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end(); ++iter)
00206                                         {
00207                                                 AISNavigation::TreePoseGraph2::Vertex* v=pg2.vertex(iter->first);
00208                                                 float roll, pitch, yaw;
00209                                                 iter->second.getEulerAngles(roll, pitch, yaw);
00210                                                 Transform newPose(v->pose.x(), v->pose.y(), iter->second.z(), roll, pitch, v->pose.theta());
00211 
00212                                                 UASSERT_MSG(!newPose.isNull(), uFormat("Optimized pose %d is null!?!?", iter->first).c_str());
00213                                                 tmpPoses.insert(std::pair<int, Transform>(iter->first, newPose));
00214                                         }
00215                                 }
00216                                 else
00217                                 {
00218                                         for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end(); ++iter)
00219                                         {
00220                                                 AISNavigation::TreePoseGraph3::Vertex* v=pg3.vertex(iter->first);
00221                                                 AISNavigation::TreePoseGraph3::Pose pose=v->transformation.toPoseType();
00222                                                 Transform newPose(pose.x(), pose.y(), pose.z(), pose.roll(), pose.pitch(), pose.yaw());
00223 
00224                                                 UASSERT_MSG(!newPose.isNull(), uFormat("Optimized pose %d is null!?!?", iter->first).c_str());
00225                                                 tmpPoses.insert(std::pair<int, Transform>(iter->first, newPose));
00226                                         }
00227                                 }
00228                                 intermediateGraphes->push_back(tmpPoses);
00229                         }
00230 
00231                         double error = 0;
00232                         if(isSlam2d())
00233                         {
00234                                 pg2.iterate();
00235 
00236                                 // compute the error and dump it
00237                                 error=pg2.error();
00238                                 UDEBUG("iteration %d global error=%f error/constraint=%f", i, error, error/pg2.edges.size());
00239                         }
00240                         else
00241                         {
00242                                 pg3.iterate();
00243 
00244                                 // compute the error and dump it
00245                                 double mte, mre, are, ate;
00246                                 error=pg3.error(&mre, &mte, &are, &ate);
00247                                 UDEBUG("i %d RotGain=%f global error=%f error/constraint=%f",
00248                                                 i, pg3.getRotGain(), error, error/pg3.edges.size());
00249                         }
00250 
00251                         // early stop condition
00252                         double errorDelta = lastError - error;
00253                         if(i>0 && errorDelta < this->epsilon())
00254                         {
00255                                 if(errorDelta < 0)
00256                                 {
00257                                         UDEBUG("Negative improvement?! Ignore and continue optimizing... (%f < %f)", errorDelta, this->epsilon());
00258                                 }
00259                                 else
00260                                 {
00261                                         UINFO("Stop optimizing, not enough improvement (%f < %f)", errorDelta, this->epsilon());
00262                                         break;
00263                                 }
00264                         }
00265                         else if(i==0 && error < this->epsilon())
00266                         {
00267                                 UINFO("Stop optimizing, error is already under epsilon (%f < %f)", error, this->epsilon());
00268                                 break;
00269                         }
00270                         lastError = error;
00271                 }
00272                 if(finalError)
00273                 {
00274                         *finalError = lastError;
00275                 }
00276                 if(iterationsDone)
00277                 {
00278                         *iterationsDone = i;
00279                 }
00280                 UINFO("TORO optimizing end (%d iterations done, error=%f, time = %f s)", i, lastError, timer.ticks());
00281 
00282                 if(isSlam2d())
00283                 {
00284                         for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end(); ++iter)
00285                         {
00286                                 AISNavigation::TreePoseGraph2::Vertex* v=pg2.vertex(iter->first);
00287                                 float roll, pitch, yaw;
00288                                 iter->second.getEulerAngles(roll, pitch, yaw);
00289                                 Transform newPose(v->pose.x(), v->pose.y(), iter->second.z(), roll, pitch, v->pose.theta());
00290 
00291                                 UASSERT_MSG(!newPose.isNull(), uFormat("Optimized pose %d is null!?!?", iter->first).c_str());
00292                                 optimizedPoses.insert(std::pair<int, Transform>(iter->first, newPose));
00293                         }
00294                 }
00295                 else
00296                 {
00297                         for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end(); ++iter)
00298                         {
00299                                 AISNavigation::TreePoseGraph3::Vertex* v=pg3.vertex(iter->first);
00300                                 AISNavigation::TreePoseGraph3::Pose pose=v->transformation.toPoseType();
00301                                 Transform newPose(pose.x(), pose.y(), pose.z(), pose.roll(), pose.pitch(), pose.yaw());
00302 
00303                                 UASSERT_MSG(!newPose.isNull(), uFormat("Optimized pose %d is null!?!?", iter->first).c_str());
00304                                 optimizedPoses.insert(std::pair<int, Transform>(iter->first, newPose));
00305                         }
00306                 }
00307         }
00308         else if(poses.size() == 1 || iterations() <= 0)
00309         {
00310                 optimizedPoses = poses;
00311         }
00312         else
00313         {
00314                 UWARN("This method should be called at least with 1 pose!");
00315         }
00316         UDEBUG("Optimizing graph...end!");
00317 #else
00318         UERROR("Not built with TORO support!");
00319 #endif
00320         return optimizedPoses;
00321 }
00322 
00323 bool OptimizerTORO::saveGraph(
00324                 const std::string & fileName,
00325                 const std::map<int, Transform> & poses,
00326                 const std::multimap<int, Link> & edgeConstraints)
00327 {
00328         FILE * file = 0;
00329 
00330 #ifdef _MSC_VER
00331         fopen_s(&file, fileName.c_str(), "w");
00332 #else
00333         file = fopen(fileName.c_str(), "w");
00334 #endif
00335 
00336         if(file)
00337         {
00338                 // VERTEX3 id x y z phi theta psi
00339                 for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end(); ++iter)
00340                 {
00341                         float x,y,z, yaw,pitch,roll;
00342                         iter->second.getTranslationAndEulerAngles(x,y,z, roll, pitch, yaw);
00343                         fprintf(file, "VERTEX3 %d %f %f %f %f %f %f\n",
00344                                         iter->first,
00345                                         x,
00346                                         y,
00347                                         z,
00348                                         roll,
00349                                         pitch,
00350                                         yaw);
00351                 }
00352 
00353                 //EDGE3 observed_vertex_id observing_vertex_id x y z roll pitch yaw inf_11 inf_12 .. inf_16 inf_22 .. inf_66
00354                 for(std::multimap<int, Link>::const_iterator iter = edgeConstraints.begin(); iter!=edgeConstraints.end(); ++iter)
00355                 {
00356                         float x,y,z, yaw,pitch,roll;
00357                         iter->second.transform().getTranslationAndEulerAngles(x,y,z, roll, pitch, yaw);
00358                         fprintf(file, "EDGE3 %d %d %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f\n",
00359                                         iter->first,
00360                                         iter->second.to(),
00361                                         x,
00362                                         y,
00363                                         z,
00364                                         roll,
00365                                         pitch,
00366                                         yaw,
00367                                         iter->second.infMatrix().at<double>(0,0),
00368                                         iter->second.infMatrix().at<double>(0,1),
00369                                         iter->second.infMatrix().at<double>(0,2),
00370                                         iter->second.infMatrix().at<double>(0,3),
00371                                         iter->second.infMatrix().at<double>(0,4),
00372                                         iter->second.infMatrix().at<double>(0,5),
00373                                         iter->second.infMatrix().at<double>(1,1),
00374                                         iter->second.infMatrix().at<double>(1,2),
00375                                         iter->second.infMatrix().at<double>(1,3),
00376                                         iter->second.infMatrix().at<double>(1,4),
00377                                         iter->second.infMatrix().at<double>(1,5),
00378                                         iter->second.infMatrix().at<double>(2,2),
00379                                         iter->second.infMatrix().at<double>(2,3),
00380                                         iter->second.infMatrix().at<double>(2,4),
00381                                         iter->second.infMatrix().at<double>(2,5),
00382                                         iter->second.infMatrix().at<double>(3,3),
00383                                         iter->second.infMatrix().at<double>(3,4),
00384                                         iter->second.infMatrix().at<double>(3,5),
00385                                         iter->second.infMatrix().at<double>(4,4),
00386                                         iter->second.infMatrix().at<double>(4,5),
00387                                         iter->second.infMatrix().at<double>(5,5));
00388                 }
00389                 UINFO("Graph saved to %s", fileName.c_str());
00390                 fclose(file);
00391         }
00392         else
00393         {
00394                 UERROR("Cannot save to file %s", fileName.c_str());
00395                 return false;
00396         }
00397         return true;
00398 }
00399 
00400 bool OptimizerTORO::loadGraph(
00401                 const std::string & fileName,
00402                 std::map<int, Transform> & poses,
00403                 std::multimap<int, Link> & edgeConstraints)
00404 {
00405         FILE * file = 0;
00406 #ifdef _MSC_VER
00407         fopen_s(&file, fileName.c_str(), "r");
00408 #else
00409         file = fopen(fileName.c_str(), "r");
00410 #endif
00411 
00412         if(file)
00413         {
00414                 char line[400];
00415                 while ( fgets (line , 400 , file) != NULL )
00416                 {
00417                         std::vector<std::string> strList = uListToVector(uSplit(uReplaceChar(line, '\n', ' '), ' '));
00418                         if(strList.size() == 8)
00419                         {
00420                                 //VERTEX3
00421                                 int id = atoi(strList[1].c_str());
00422                                 float x = uStr2Float(strList[2]);
00423                                 float y = uStr2Float(strList[3]);
00424                                 float z = uStr2Float(strList[4]);
00425                                 float roll = uStr2Float(strList[5]);
00426                                 float pitch = uStr2Float(strList[6]);
00427                                 float yaw = uStr2Float(strList[7]);
00428                                 Transform pose(x, y, z, roll, pitch, yaw);
00429                                 if(poses.find(id) == poses.end())
00430                                 {
00431                                         poses.insert(std::make_pair(id, pose));
00432                                 }
00433                                 else
00434                                 {
00435                                         UFATAL("Pose %d already added", id);
00436                                 }
00437                         }
00438                         else if(strList.size() == 30)
00439                         {
00440                                 //EDGE3
00441                                 int idFrom = atoi(strList[1].c_str());
00442                                 int idTo = atoi(strList[2].c_str());
00443                                 float x = uStr2Float(strList[3]);
00444                                 float y = uStr2Float(strList[4]);
00445                                 float z = uStr2Float(strList[5]);
00446                                 float roll = uStr2Float(strList[6]);
00447                                 float pitch = uStr2Float(strList[7]);
00448                                 float yaw = uStr2Float(strList[8]);
00449                                 float infR = uStr2Float(strList[9]);
00450                                 float infP = uStr2Float(strList[15]);
00451                                 float infW = uStr2Float(strList[20]);
00452                                 UASSERT_MSG(infR > 0 && infP > 0 && infW > 0, uFormat("Information matrix should not be null! line=\"%s\"", line).c_str());
00453                                 float rotVariance = infR<=infP && infR<=infW?infR:infP<=infW?infP:infW; // maximum variance
00454                                 float infX = uStr2Float(strList[24]);
00455                                 float infY = uStr2Float(strList[27]);
00456                                 float infZ = uStr2Float(strList[29]);
00457                                 UASSERT_MSG(infX > 0 && infY > 0 && infZ > 0, uFormat("Information matrix should not be null! line=\"%s\"", line).c_str());
00458                                 float transVariance = 1.0f/(infX<=infY && infX<=infZ?infX:infY<=infW?infY:infZ); // maximum variance
00459                                 UINFO("id=%d rotV=%f transV=%f", idFrom, rotVariance, transVariance);
00460                                 Transform transform(x, y, z, roll, pitch, yaw);
00461                                 if(poses.find(idFrom) != poses.end() && poses.find(idTo) != poses.end())
00462                                 {
00463                                         //Link type is unknown
00464                                         Link link(idFrom, idTo, Link::kUndef, transform, rotVariance, transVariance);
00465                                         edgeConstraints.insert(std::pair<int, Link>(idFrom, link));
00466                                 }
00467                                 else
00468                                 {
00469                                         UFATAL("Referred poses from the link not exist!");
00470                                 }
00471                         }
00472                         else if(strList.size())
00473                         {
00474                                 UFATAL("Error parsing graph file %s on line \"%s\" (strList.size()=%d)", fileName.c_str(), line, (int)strList.size());
00475                         }
00476                 }
00477 
00478                 UINFO("Graph loaded from %s", fileName.c_str());
00479                 fclose(file);
00480         }
00481         else
00482         {
00483                 UERROR("Cannot open file %s", fileName.c_str());
00484                 return false;
00485         }
00486         return true;
00487 }
00488 
00489 } /* namespace rtabmap */


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