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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:13