OptimizerCVSBA.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/OptimizerCVSBA.h>
00037 
00038 #ifdef RTABMAP_CVSBA
00039 #include <cvsba/cvsba.h>
00040 #include "rtabmap/core/util3d_motion_estimation.h"
00041 #include "rtabmap/core/util3d_transforms.h"
00042 #include "rtabmap/core/util3d_correspondences.h"
00043 #endif
00044 
00045 namespace rtabmap {
00046 
00047 bool OptimizerCVSBA::available()
00048 {
00049 #ifdef RTABMAP_CVSBA
00050         return true;
00051 #else
00052         return false;
00053 #endif
00054 }
00055 
00056 std::map<int, Transform> OptimizerCVSBA::optimizeBA(
00057                 int rootId,
00058                 const std::map<int, Transform> & poses,
00059                 const std::multimap<int, Link> & links,
00060                 const std::map<int, CameraModel> & models,
00061                 std::map<int, cv::Point3f> & points3DMap,
00062                 const std::map<int, std::map<int, cv::Point3f> > & wordReferences, // <ID words, IDs frames + keypoint/Disparity>)
00063                 std::set<int> * outliers)
00064 {
00065 #ifdef RTABMAP_CVSBA
00066         // run sba optimization
00067         cvsba::Sba sba;
00068 
00069         // change params if desired
00070         cvsba::Sba::Params params ;
00071         params.type = cvsba::Sba::MOTIONSTRUCTURE;
00072         params.iterations = this->iterations();
00073         params.minError = this->epsilon();
00074         params.fixedIntrinsics = 5;
00075         params.fixedDistortion = 5; // updated below
00076         params.verbose=ULogger::level() <= ULogger::kInfo;
00077         sba.setParams(params);
00078 
00079         std::vector<cv::Mat> cameraMatrix(poses.size()); //nframes
00080         std::vector<cv::Mat> R(poses.size()); //nframes
00081         std::vector<cv::Mat> T(poses.size()); //nframes
00082         std::vector<cv::Mat> distCoeffs(poses.size()); //nframes
00083         std::map<int, int> frameIdToIndex;
00084         int oi=0;
00085         for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
00086         {
00087                 // Get camera model
00088                 std::map<int, CameraModel>::const_iterator iterModel = models.find(iter->first);
00089                 UASSERT(iterModel != models.end() && iterModel->second.isValidForProjection());
00090 
00091                 frameIdToIndex.insert(std::make_pair(iter->first, oi));
00092 
00093                 cameraMatrix[oi] = iterModel->second.K();
00094                 if(iterModel->second.D().cols != 5)
00095                 {
00096                         distCoeffs[oi] = cv::Mat::zeros(1, 5, CV_64FC1);
00097                         UWARN("Camera model %d: Distortion coefficients are not 5, setting all them to 0 (assuming no distortion)", iter->first);
00098                 }
00099                 else
00100                 {
00101                         distCoeffs[oi] = iterModel->second.D();
00102                 }
00103 
00104                 Transform t = (iter->second * iterModel->second.localTransform()).inverse();
00105 
00106                 R[oi] = (cv::Mat_<double>(3,3) <<
00107                                 (double)t.r11(), (double)t.r12(), (double)t.r13(),
00108                                 (double)t.r21(), (double)t.r22(), (double)t.r23(),
00109                                 (double)t.r31(), (double)t.r32(), (double)t.r33());
00110                 T[oi] = (cv::Mat_<double>(1,3) << (double)t.x(), (double)t.y(), (double)t.z());
00111                 ++oi;
00112 
00113                 UDEBUG("Pose %d = %s", iter->first, t.prettyPrint().c_str());
00114         }
00115         cameraMatrix.resize(oi);
00116         R.resize(oi);
00117         T.resize(oi);
00118         distCoeffs.resize(oi);
00119 
00120         UDEBUG("points=%d frames=%d", (int)points3DMap.size(), (int)poses.size());
00121         std::vector<cv::Point3f> points(points3DMap.size()); //npoints
00122         std::vector<std::vector<cv::Point2f> >  imagePoints(poses.size()); //nframes -> npoints
00123         std::vector<std::vector<int> > visibility(poses.size()); //nframes -> npoints
00124         for(unsigned int i=0; i<poses.size(); ++i)
00125         {
00126                 imagePoints[i].resize(wordReferences.size(), cv::Point2f(std::numeric_limits<float>::quiet_NaN(), std::numeric_limits<float>::quiet_NaN()));
00127                 visibility[i].resize(wordReferences.size(), 0);
00128         }
00129         int i=0;
00130         for(std::map<int, cv::Point3f>::const_iterator kter = points3DMap.begin(); kter!=points3DMap.end(); ++kter)
00131         {
00132                 points[i] = kter->second;
00133 
00134                 std::map<int, std::map<int, cv::Point3f> >::const_iterator iter = wordReferences.find(kter->first);
00135                 if(iter != wordReferences.end())
00136                 {
00137                         for(std::map<int, cv::Point3f>::const_iterator jter=iter->second.begin(); jter!=iter->second.end(); ++jter)
00138                         {
00139                                 if(frameIdToIndex.find(jter->first) != frameIdToIndex.end())
00140                                 {
00141                                         imagePoints[frameIdToIndex.at(jter->first)][i] = cv::Point2f(jter->second.x, jter->second.y);
00142                                         visibility[frameIdToIndex.at(jter->first)][i] = 1;
00143                                 }
00144                         }
00145                 }
00146                 ++i;
00147         }
00148 
00149         // SBA
00150         try
00151         {
00152                 sba.run( points, imagePoints, visibility, cameraMatrix, R, T, distCoeffs);
00153         }
00154         catch(cv::Exception & e)
00155         {
00156                 UERROR("Running SBA... error! %s", e.what());
00157                 return std::map<int, Transform>();
00158         }
00159 
00160         //update poses
00161         i=0;
00162         std::map<int, Transform> newPoses = poses;
00163         for(std::map<int, Transform>::iterator iter=newPoses.begin(); iter!=newPoses.end(); ++iter)
00164         {
00165                 Transform t(R[i].at<double>(0,0), R[i].at<double>(0,1), R[i].at<double>(0,2), T[i].at<double>(0),
00166                                         R[i].at<double>(1,0), R[i].at<double>(1,1), R[i].at<double>(1,2), T[i].at<double>(1),
00167                                         R[i].at<double>(2,0), R[i].at<double>(2,1), R[i].at<double>(2,2), T[i].at<double>(2));
00168 
00169                 UDEBUG("New pose %d = %s", iter->first, t.prettyPrint().c_str());
00170 
00171                 if(this->isSlam2d())
00172                 {
00173                         t = (models.at(iter->first).localTransform() * t).inverse();
00174                         t = iter->second.inverse() * t;
00175                         iter->second *= t.to3DoF();
00176                 }
00177                 else
00178                 {
00179                         iter->second = (models.at(iter->first).localTransform() * t).inverse();
00180                 }
00181 
00182                 ++i;
00183         }
00184 
00185         //update 3D points
00186         i=0;
00187         for(std::map<int, cv::Point3f>::iterator kter = points3DMap.begin(); kter!=points3DMap.end(); ++kter)
00188         {
00189                 kter->second = points[i++];
00190         }
00191 
00192         return newPoses;
00193 
00194 #else
00195         UERROR("RTAB-Map is not built with cvsba!");
00196         return std::map<int, Transform>();
00197 #endif
00198 }
00199 
00200 } /* namespace rtabmap */


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