OdometryDVO.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 
30 #include "rtabmap/core/util2d.h"
32 #include "rtabmap/utilite/UTimer.h"
33 #include "rtabmap/utilite/UStl.h"
34 
35 #ifdef RTABMAP_DVO
36 #include <dvo/dense_tracking.h>
37 #include <dvo/core/surface_pyramid.h>
38 #include <dvo/core/rgbd_image.h>
39 #endif
40 
41 namespace rtabmap {
42 
44  Odometry(parameters),
45 #ifdef RTABMAP_DVO
46  dvo_(0),
47  reference_(0),
48  camera_(0),
49  lost_(false),
50 #endif
51  motionFromKeyFrame_(Transform::getIdentity())
52 {
53 }
54 
56 {
57 #ifdef RTABMAP_DVO
58  delete dvo_;
59  delete reference_;
60  delete camera_;
61 #endif
62 }
63 
64 void OdometryDVO::reset(const Transform & initialPose)
65 {
66  Odometry::reset(initialPose);
67 #ifdef RTABMAP_DVO
68  if(dvo_)
69  {
70  delete dvo_;
71  dvo_ = 0;
72  }
73  if(reference_)
74  {
75  delete reference_;
76  reference_ = 0;
77  }
78  if(camera_)
79  {
80  delete camera_;
81  camera_ = 0;
82  }
83  lost_ = false;
86 #endif
87 }
88 
89 // return not null transform if odometry is correctly computed
91  SensorData & data,
92  const Transform & guess,
93  OdometryInfo * info)
94 {
95  Transform t;
96 
97 #ifdef RTABMAP_DVO
98  UTimer timer;
99 
100  if(data.imageRaw().empty() ||
101  data.imageRaw().rows != data.depthOrRightRaw().rows ||
102  data.imageRaw().cols != data.depthOrRightRaw().cols)
103  {
104  UERROR("Not supported input!");
105  return t;
106  }
107 
108  if(!(data.cameraModels().size() == 1 && data.cameraModels()[0].isValidForReprojection()))
109  {
110  UERROR("Invalid camera model! Only single RGB-D camera supported by DVO. Try another odometry approach.");
111  return t;
112  }
113 
114  if(dvo_ == 0)
115  {
116  dvo::DenseTracker::Config cfg = dvo::DenseTracker::getDefaultConfig();
117 
118  dvo_ = new dvo::DenseTracker(cfg);
119  }
120 
121  cv::Mat grey, grey_s16, depth_inpainted, depth_mask, depth_mono, depth_float;
122  if(data.imageRaw().type() != CV_32FC1)
123  {
124  if(data.imageRaw().type() == CV_8UC3)
125  {
126  cv::cvtColor(data.imageRaw(), grey, CV_BGR2GRAY);
127  }
128  else
129  {
130  grey = data.imageRaw();
131  }
132 
133  grey.convertTo(grey_s16, CV_32F);
134  }
135  else
136  {
137  grey_s16 = data.imageRaw();
138  }
139 
140  // make sure all zeros are NAN
141  if(data.depthRaw().type() == CV_32FC1)
142  {
143  depth_float = data.depthRaw();
144  for(int i=0; i<depth_float.rows; ++i)
145  {
146  for(int j=0; j<depth_float.cols; ++j)
147  {
148  float & d = depth_float.at<float>(i,j);
149  if(d == 0.0f)
150  {
151  d = NAN;
152  }
153  }
154  }
155  }
156  else if(data.depthRaw().type() == CV_16UC1)
157  {
158  depth_float = cv::Mat(data.depthRaw().size(), CV_32FC1);
159  for(int i=0; i<data.depthRaw().rows; ++i)
160  {
161  for(int j=0; j<data.depthRaw().cols; ++j)
162  {
163  float d = float(data.depthRaw().at<unsigned short>(i,j))/1000.0f;
164  depth_float.at<float>(i, j) = d==0.0f?NAN:d;
165  }
166  }
167  }
168  else
169  {
170  UFATAL("Unknown depth format!");
171  }
172 
173  if(camera_ == 0)
174  {
175  dvo::core::IntrinsicMatrix intrinsics = dvo::core::IntrinsicMatrix::create(
176  data.cameraModels()[0].fx(),
177  data.cameraModels()[0].fy(),
178  data.cameraModels()[0].cx(),
179  data.cameraModels()[0].cy());
180  camera_ = new dvo::core::RgbdCameraPyramid(
181  data.cameraModels()[0].imageWidth(),
182  data.cameraModels()[0].imageHeight(),
183  intrinsics);
184  }
185 
186  dvo::core::RgbdImagePyramid * current = new dvo::core::RgbdImagePyramid(*camera_, grey_s16, depth_float);
187 
188  const Transform & localTransform = data.cameraModels()[0].localTransform();
189  cv::Mat covariance;
190  if(reference_ == 0)
191  {
192  reference_ = current;
193  if(!lost_)
194  {
195  t.setIdentity();
196  }
197  covariance = cv::Mat::eye(6,6,CV_64FC1) * 9999.0;
198  }
199  else
200  {
201  dvo::DenseTracker::Result result;
202  dvo_->match(*reference_, *current, result);
203  t = Transform::fromEigen3d(result.Transformation);
204 
205  if(result.Information(0,0) > 0.0 && result.Information(0,0) != 1.0)
206  {
207  lost_ = false;
208  cv::Mat information = cv::Mat::eye(6,6, CV_64FC1);
209  memcpy(information.data, result.Information.data(), 36*sizeof(double));
210  //copy only diagonal to avoid g2o/gtsam errors on graph optimization
211  covariance = cv::Mat::eye(6,6,CV_64FC1);
212  covariance = information.inv().mul(covariance);
213  //covariance *= 100.0; // to be in the same scale than loop closure detection
214 
215  Transform currentMotion = t;
216  t = motionFromKeyFrame_.inverse() * t;
217 
218  // TODO make parameters?
219  if(currentMotion.getNorm() > 0.01 || currentMotion.getAngle() > 0.01)
220  {
221  if(info)
222  {
223  info->keyFrameAdded = true;
224  }
225  // new keyframe
226  delete reference_;
227  reference_ = current;
229  }
230  else
231  {
232  delete current;
233  motionFromKeyFrame_ = currentMotion;
234  }
235  }
236  else
237  {
238  lost_ = true;
239  delete reference_;
240  delete current;
241  reference_ = 0; // this will make restart from the next frame
243  t.setNull();
245  covariance = cv::Mat::eye(6,6,CV_64FC1) * 9999.0;
246  UWARN("dvo failed to estimate motion, tracking will be reinitialized on next frame.");
247  }
248 
249  if(!t.isNull() && !t.isIdentity() && !localTransform.isIdentity() && !localTransform.isNull())
250  {
251  // from camera frame to base frame
253  {
254  t = previousLocalTransform_ * t * localTransform.inverse();
255  }
256  else
257  {
258  t = localTransform * t * localTransform.inverse();
259  }
260  previousLocalTransform_ = localTransform;
261  }
262  }
263 
264  if(info)
265  {
266  info->type = (int)kTypeDVO;
267  info->reg.covariance = covariance;
268  }
269 
270  UINFO("Odom update time = %fs", timer.elapsed());
271 
272 #else
273  UERROR("RTAB-Map is not built with DVO support! Select another visual odometry approach.");
274 #endif
275  return t;
276 }
277 
278 } // namespace rtabmap
d
Definition: UTimer.h:46
double elapsed()
Definition: UTimer.h:75
f
virtual void reset(const Transform &initialPose=Transform::getIdentity())
Definition: Odometry.cpp:182
virtual Transform computeTransform(SensorData &image, const Transform &guess=Transform(), OdometryInfo *info=0)
Definition: OdometryDVO.cpp:90
float getNorm() const
Definition: Transform.cpp:231
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
const cv::Mat & imageRaw() const
Definition: SensorData.h:161
#define UFATAL(...)
bool isIdentity() const
Definition: Transform.cpp:136
Wrappers of STL for convenient functions.
bool isNull() const
Definition: Transform.cpp:107
OdometryDVO(const rtabmap::ParametersMap &parameters=rtabmap::ParametersMap())
Definition: OdometryDVO.cpp:43
Transform previousLocalTransform_
Definition: OdometryDVO.h:63
const cv::Mat & depthOrRightRaw() const
Definition: SensorData.h:162
Transform motionFromKeyFrame_
Definition: OdometryDVO.h:62
static Transform fromEigen3d(const Eigen::Affine3d &matrix)
Definition: Transform.cpp:388
#define false
Definition: ConvertUTF.c:56
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:193
#define UERROR(...)
ULogger class and convenient macros.
#define UWARN(...)
virtual void reset(const Transform &initialPose=Transform::getIdentity())
Definition: OdometryDVO.cpp:64
float getAngle(float x=1.0f, float y=0.0f, float z=0.0f) const
Definition: Transform.cpp:224
RegistrationInfo reg
Definition: OdometryInfo.h:91
Transform inverse() const
Definition: Transform.cpp:169
cv::Mat depthRaw() const
Definition: SensorData.h:172
#define UINFO(...)


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