OptimizerCVSBA.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 #include "rtabmap/core/Graph.h"
28 
30 #include <rtabmap/utilite/UStl.h>
31 #include <rtabmap/utilite/UMath.h>
33 #include <rtabmap/utilite/UTimer.h>
34 #include <set>
35 
37 
38 #ifdef RTABMAP_CVSBA
39 #include <cvsba/cvsba.h>
43 #endif
44 
45 namespace rtabmap {
46 
48 {
49 #ifdef RTABMAP_CVSBA
50  return true;
51 #else
52  return false;
53 #endif
54 }
55 
56 std::map<int, Transform> OptimizerCVSBA::optimizeBA(
57  int rootId,
58  const std::map<int, Transform> & poses,
59  const std::multimap<int, Link> & links,
60  const std::map<int, CameraModel> & models,
61  std::map<int, cv::Point3f> & points3DMap,
62  const std::map<int, std::map<int, cv::Point3f> > & wordReferences, // <ID words, IDs frames + keypoint/Disparity>)
63  std::set<int> * outliers)
64 {
65 #ifdef RTABMAP_CVSBA
66  // run sba optimization
67  cvsba::Sba sba;
68 
69  // change params if desired
70  cvsba::Sba::Params params ;
71  params.type = cvsba::Sba::MOTIONSTRUCTURE;
72  params.iterations = this->iterations();
73  params.minError = this->epsilon();
74  params.fixedIntrinsics = 5;
75  params.fixedDistortion = 5; // updated below
76  params.verbose=ULogger::level() <= ULogger::kInfo;
77  sba.setParams(params);
78 
79  std::vector<cv::Mat> cameraMatrix(poses.size()); //nframes
80  std::vector<cv::Mat> R(poses.size()); //nframes
81  std::vector<cv::Mat> T(poses.size()); //nframes
82  std::vector<cv::Mat> distCoeffs(poses.size()); //nframes
83  std::map<int, int> frameIdToIndex;
84  int oi=0;
85  for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
86  {
87  // Get camera model
88  std::map<int, CameraModel>::const_iterator iterModel = models.find(iter->first);
89  UASSERT(iterModel != models.end() && iterModel->second.isValidForProjection());
90 
91  frameIdToIndex.insert(std::make_pair(iter->first, oi));
92 
93  cameraMatrix[oi] = iterModel->second.K();
94  if(iterModel->second.D().cols != 5)
95  {
96  distCoeffs[oi] = cv::Mat::zeros(1, 5, CV_64FC1);
97  UWARN("Camera model %d: Distortion coefficients are not 5, setting all them to 0 (assuming no distortion)", iter->first);
98  }
99  else
100  {
101  distCoeffs[oi] = iterModel->second.D();
102  }
103 
104  Transform t = (iter->second * iterModel->second.localTransform()).inverse();
105 
106  R[oi] = (cv::Mat_<double>(3,3) <<
107  (double)t.r11(), (double)t.r12(), (double)t.r13(),
108  (double)t.r21(), (double)t.r22(), (double)t.r23(),
109  (double)t.r31(), (double)t.r32(), (double)t.r33());
110  T[oi] = (cv::Mat_<double>(1,3) << (double)t.x(), (double)t.y(), (double)t.z());
111  ++oi;
112 
113  UDEBUG("Pose %d = %s", iter->first, t.prettyPrint().c_str());
114  }
115  cameraMatrix.resize(oi);
116  R.resize(oi);
117  T.resize(oi);
118  distCoeffs.resize(oi);
119 
120  UDEBUG("points=%d frames=%d", (int)points3DMap.size(), (int)poses.size());
121  std::vector<cv::Point3f> points(points3DMap.size()); //npoints
122  std::vector<std::vector<cv::Point2f> > imagePoints(poses.size()); //nframes -> npoints
123  std::vector<std::vector<int> > visibility(poses.size()); //nframes -> npoints
124  for(unsigned int i=0; i<poses.size(); ++i)
125  {
126  imagePoints[i].resize(wordReferences.size(), cv::Point2f(std::numeric_limits<float>::quiet_NaN(), std::numeric_limits<float>::quiet_NaN()));
127  visibility[i].resize(wordReferences.size(), 0);
128  }
129  int i=0;
130  for(std::map<int, cv::Point3f>::const_iterator kter = points3DMap.begin(); kter!=points3DMap.end(); ++kter)
131  {
132  points[i] = kter->second;
133 
134  std::map<int, std::map<int, cv::Point3f> >::const_iterator iter = wordReferences.find(kter->first);
135  if(iter != wordReferences.end())
136  {
137  for(std::map<int, cv::Point3f>::const_iterator jter=iter->second.begin(); jter!=iter->second.end(); ++jter)
138  {
139  if(frameIdToIndex.find(jter->first) != frameIdToIndex.end())
140  {
141  imagePoints[frameIdToIndex.at(jter->first)][i] = cv::Point2f(jter->second.x, jter->second.y);
142  visibility[frameIdToIndex.at(jter->first)][i] = 1;
143  }
144  }
145  }
146  ++i;
147  }
148 
149  // SBA
150  try
151  {
152  sba.run( points, imagePoints, visibility, cameraMatrix, R, T, distCoeffs);
153  }
154  catch(cv::Exception & e)
155  {
156  UERROR("Running SBA... error! %s", e.what());
157  return std::map<int, Transform>();
158  }
159 
160  //update poses
161  i=0;
162  std::map<int, Transform> newPoses = poses;
163  for(std::map<int, Transform>::iterator iter=newPoses.begin(); iter!=newPoses.end(); ++iter)
164  {
165  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),
166  R[i].at<double>(1,0), R[i].at<double>(1,1), R[i].at<double>(1,2), T[i].at<double>(1),
167  R[i].at<double>(2,0), R[i].at<double>(2,1), R[i].at<double>(2,2), T[i].at<double>(2));
168 
169  UDEBUG("New pose %d = %s", iter->first, t.prettyPrint().c_str());
170 
171  if(this->isSlam2d())
172  {
173  t = (models.at(iter->first).localTransform() * t).inverse();
174  t = iter->second.inverse() * t;
175  iter->second *= t.to3DoF();
176  }
177  else
178  {
179  iter->second = (models.at(iter->first).localTransform() * t).inverse();
180  }
181 
182  ++i;
183  }
184 
185  //update 3D points
186  i=0;
187  for(std::map<int, cv::Point3f>::iterator kter = points3DMap.begin(); kter!=points3DMap.end(); ++kter)
188  {
189  kter->second = points[i++];
190  }
191 
192  return newPoses;
193 
194 #else
195  UERROR("RTAB-Map is not built with cvsba!");
196  return std::map<int, Transform>();
197 #endif
198 }
199 
200 } /* namespace rtabmap */
float r13() const
Definition: Transform.h:63
float r23() const
Definition: Transform.h:66
std::string prettyPrint() const
Definition: Transform.cpp:274
bool isSlam2d() const
Definition: Optimizer.h:74
GLM_FUNC_DECL genType e()
Basic mathematics functions.
Some conversion functions.
#define UASSERT(condition)
Wrappers of STL for convenient functions.
virtual std::map< int, Transform > optimizeBA(int rootId, const std::map< int, Transform > &poses, const std::multimap< int, Link > &links, const std::map< int, CameraModel > &models, std::map< int, cv::Point3f > &points3DMap, const std::map< int, std::map< int, cv::Point3f > > &wordReferences, std::set< int > *outliers=0)
float r12() const
Definition: Transform.h:62
float r31() const
Definition: Transform.h:67
double epsilon() const
Definition: Optimizer.h:76
int iterations() const
Definition: Optimizer.h:73
static ULogger::Level level()
Definition: ULogger.h:340
float r21() const
Definition: Transform.h:64
float r33() const
Definition: Transform.h:69
Transform to3DoF() const
Definition: Transform.cpp:189
#define UDEBUG(...)
float r22() const
Definition: Transform.h:65
#define UERROR(...)
ULogger class and convenient macros.
#define UWARN(...)
Transform inverse() const
Definition: Transform.cpp:169
float r11() const
Definition: Transform.h:61
float r32() const
Definition: Transform.h:68
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:32