OdometryViso2.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_VISO2
37 #include <viso_stereo.h>
38 
39 double computeFeatureFlow(const std::vector<Matcher::p_match>& matches)
40  {
41  double total_flow = 0.0;
42  for (size_t i = 0; i < matches.size(); ++i)
43  {
44  double x_diff = matches[i].u1c - matches[i].u1p;
45  double y_diff = matches[i].v1c - matches[i].v1p;
46  total_flow += sqrt(x_diff * x_diff + y_diff * y_diff);
47  }
48  return total_flow / matches.size();
49 }
50 #endif
51 
52 namespace rtabmap {
53 
55  Odometry(parameters),
56 #ifdef RTABMAP_VISO2
57  viso2_(0),
58  ref_frame_change_method_(0),
59  ref_frame_inlier_threshold_(Parameters::defaultOdomVisKeyFrameThr()),
60  ref_frame_motion_threshold_(5.0),
61  lost_(false),
62  keep_reference_frame_(false),
63 #endif
64  reference_motion_(Transform::getIdentity())
65 {
66 #ifdef RTABMAP_VISO2
67  Parameters::parse(parameters, Parameters::kOdomVisKeyFrameThr(), ref_frame_inlier_threshold_);
68 #endif
69  viso2Parameters_ = Parameters::filterParameters(parameters, "OdomViso2");
70 }
71 
73 {
74 #ifdef RTABMAP_VISO2
75  delete viso2_;
76 #endif
77 }
78 
79 void OdometryViso2::reset(const Transform & initialPose)
80 {
81  Odometry::reset(initialPose);
82 #ifdef RTABMAP_VISO2
83  if(viso2_)
84  {
85  delete viso2_;
86  viso2_ = 0;
87  }
88  lost_ = false;
91 #endif
92 }
93 
94 // return not null transform if odometry is correctly computed
96  SensorData & data,
97  const Transform & guess,
98  OdometryInfo * info)
99 {
100  Transform t;
101 #ifdef RTABMAP_VISO2
102  //based on https://github.com/srv/viso2/blob/indigo/viso2_ros/src/stereo_odometer.cpp
103 
104  UTimer timer;
105 
106  if(!data.depthRaw().empty())
107  {
108  UERROR("viso2 odometry doesn't support RGB-D data, only stereo. Aborting odometry update...");
109  return t;
110  }
111 
112  if(data.imageRaw().empty() ||
113  data.imageRaw().rows != data.rightRaw().rows ||
114  data.imageRaw().cols != data.rightRaw().cols)
115  {
116  UERROR("Not compatible left (%dx%d) or right (%dx%d) image.",
117  data.imageRaw().rows,
118  data.imageRaw().cols,
119  data.rightRaw().rows,
120  data.rightRaw().cols);
121  return t;
122  }
123 
124  if(!(data.stereoCameraModel().isValidForProjection() &&
127  {
128  UERROR("Invalid stereo camera model!");
129  return t;
130  }
131 
132  cv::Mat leftGray;
133  if(data.imageRaw().type() == CV_8UC3)
134  {
135  cv::cvtColor(data.imageRaw(), leftGray, CV_BGR2GRAY);
136  }
137  else if(data.imageRaw().type() == CV_8UC1)
138  {
139  leftGray = data.imageRaw();
140  }
141  else
142  {
143  UFATAL("Not supported color type!");
144  }
145  cv::Mat rightGray;
146  if(data.rightRaw().type() == CV_8UC3)
147  {
148  cv::cvtColor(data.rightRaw(), rightGray, CV_BGR2GRAY);
149  }
150  else if(data.rightRaw().type() == CV_8UC1)
151  {
152  rightGray = data.rightRaw();
153  }
154  else
155  {
156  UFATAL("Not supported color type!");
157  }
158 
159  int32_t dims[] = {leftGray.cols, leftGray.rows, leftGray.cols};
160  cv::Mat covariance;
161  if(viso2_ == 0)
162  {
163  VisualOdometryStereo::parameters params;
164  params.base = params.match.base = data.stereoCameraModel().baseline();
165  params.calib.cu = params.match.cu = data.stereoCameraModel().left().cx();
166  params.calib.cv = params.match.cv = data.stereoCameraModel().left().cy();
167  params.calib.f = params.match.f = data.stereoCameraModel().left().fx();
168 
169  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2RansacIters(), params.ransac_iters);
170  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2InlierThreshold(), params.inlier_threshold);
171  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2Reweighting(), params.reweighting);
172 
173  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2MatchNmsN(), params.match.nms_n);
174  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2MatchNmsTau(), params.match.nms_tau);
175  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2MatchBinsize(), params.match.match_binsize);
176  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2MatchRadius(), params.match.match_radius);
177  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2MatchDispTolerance(), params.match.match_disp_tolerance);
178  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2MatchOutlierDispTolerance(), params.match.outlier_disp_tolerance);
179  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2MatchOutlierFlowTolerance(), params.match.outlier_flow_tolerance);
180  bool multistage = Parameters::defaultOdomViso2MatchMultiStage();
181  bool halfResolution = Parameters::defaultOdomViso2MatchHalfResolution();
182  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2MatchMultiStage(), multistage);
183  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2MatchHalfResolution() , halfResolution);
184  params.match.multi_stage = multistage?1:0;
185  params.match.half_resolution = halfResolution?1:0;
186  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2MatchRefinement(), params.match.refinement);
187 
188  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2BucketMaxFeatures(), params.bucket.max_features);
189  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2BucketWidth(), params.bucket.bucket_width);
190  Parameters::parse(viso2Parameters_, Parameters::kOdomViso2BucketHeight(), params.bucket.bucket_height);
191 
192  viso2_ = new VisualOdometryStereo(params);
193 
194  viso2_->process(leftGray.data, rightGray.data, dims);
195  t.setIdentity();
196  covariance = cv::Mat::eye(6,6, CV_64FC1)*9999.0;
197  }
198  else
199  {
200  bool success = viso2_->process(leftGray.data, rightGray.data, dims, lost_ || keep_reference_frame_);
201  if (success)
202  {
203  Matrix motionViso = Matrix::inv(viso2_->getMotion());
204  Transform motion(motionViso.val[0][0], motionViso.val[0][1], motionViso.val[0][2],motionViso.val[0][3],
205  motionViso.val[1][0], motionViso.val[1][1], motionViso.val[1][2],motionViso.val[1][3],
206  motionViso.val[2][0], motionViso.val[2][1], motionViso.val[2][2], motionViso.val[2][3]);
207  Transform camera_motion;
208 
209  if(lost_ || keep_reference_frame_)
210  {
211  camera_motion = reference_motion_.inverse() * motion;
212  }
213  else
214  {
215  camera_motion = motion;
216  }
217  reference_motion_ = motion; // store last motion as reference
218 
219  t=camera_motion;
220 
221  //based on values set in viso2_ros
222  covariance = cv::Mat::eye(6,6, CV_64FC1);
223  covariance.at<double>(0,0) = 0.002;
224  covariance.at<double>(1,1) = 0.002;
225  covariance.at<double>(2,2) = 0.05;
226  covariance.at<double>(3,3) = 0.09;
227  covariance.at<double>(4,4) = 0.09;
228  covariance.at<double>(5,5) = 0.09;
229 
230  lost_=false;
231  }
232  else
233  {
234  covariance = cv::Mat::eye(6,6, CV_64FC1)*9999.0;
235  lost_ = true;
236  }
237 
238  if(success)
239  {
240  // Proceed depending on the reference frame change method
241  if(ref_frame_change_method_==1)
242  {
243  // calculate current feature flow
244  double feature_flow = computeFeatureFlow(viso2_->getMatches());
245  keep_reference_frame_ = (feature_flow < ref_frame_motion_threshold_);
246  }
247  else
248  {
249  keep_reference_frame_ = ref_frame_inlier_threshold_==0 || viso2_->getNumberOfInliers() > ref_frame_inlier_threshold_;
250  }
251  }
252  else
253  {
254  keep_reference_frame_ = false;
255  }
256  }
257 
258  const Transform & localTransform = data.stereoCameraModel().localTransform();
259  if(!t.isNull() && !t.isIdentity() && !localTransform.isIdentity() && !localTransform.isNull())
260  {
261  // from camera frame to base frame
263  {
264  t = previousLocalTransform_ * t * localTransform.inverse();
265  }
266  else
267  {
268  t = localTransform * t * localTransform.inverse();
269  }
270  previousLocalTransform_ = localTransform;
271  }
272 
273  if(info)
274  {
275  info->type = (int)kTypeViso2;
276  info->keyFrameAdded = !keep_reference_frame_;
277  info->reg.matches = viso2_->getNumberOfMatches();
278  info->reg.inliers = viso2_->getNumberOfInliers();
279  if(covariance.cols == 6 && covariance.rows == 6 && covariance.type() == CV_64FC1)
280  {
281  info->reg.covariance = covariance;
282  }
283 
284  if(this->isInfoDataFilled())
285  {
286  std::vector<Matcher::p_match> matches = viso2_->getMatches();
287  info->refCorners.resize(matches.size());
288  info->newCorners.resize(matches.size());
289  info->cornerInliers.resize(matches.size());
290  for (size_t i = 0; i < matches.size(); ++i)
291  {
292  info->refCorners[i].x = matches[i].u1p;
293  info->refCorners[i].y = matches[i].v1p;
294  info->newCorners[i].x = matches[i].u1c;
295  info->newCorners[i].y = matches[i].v1c;
296  info->cornerInliers[i] = i;
297  }
298  }
299  }
300 
301  UINFO("Odom update time = %fs lost=%s", timer.elapsed(), lost_?"true":"false");
302 
303 #else
304  UERROR("RTAB-Map is not built with VISO2 support! Select another visual odometry approach.");
305 #endif
306  return t;
307 }
308 
309 } // namespace rtabmap
Transform previousLocalTransform_
Definition: OdometryViso2.h:59
static ParametersMap filterParameters(const ParametersMap &parameters, const std::string &group)
Definition: Parameters.cpp:214
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:476
std::vector< cv::Point2f > refCorners
Definition: OdometryInfo.h:128
Definition: UTimer.h:46
double elapsed()
Definition: UTimer.h:75
bool isInfoDataFilled() const
Definition: Odometry.h:74
virtual void reset(const Transform &initialPose=Transform::getIdentity())
Definition: Odometry.cpp:191
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
const cv::Mat & imageRaw() const
Definition: SensorData.h:164
#define UFATAL(...)
cv::Mat rightRaw() const
Definition: SensorData.h:190
bool isIdentity() const
Definition: Transform.cpp:136
virtual void reset(const Transform &initialPose=Transform::getIdentity())
Wrappers of STL for convenient functions.
const CameraModel & left() const
double cx() const
Definition: CameraModel.h:104
bool isNull() const
Definition: Transform.cpp:107
std::vector< int > cornerInliers
Definition: OdometryInfo.h:130
bool isValidForReprojection() const
Definition: CameraModel.h:88
double cy() const
Definition: CameraModel.h:105
#define false
Definition: ConvertUTF.c:56
detail::int32 int32_t
Definition: fwd.hpp:307
double fx() const
Definition: CameraModel.h:102
const CameraModel & right() const
ParametersMap viso2Parameters_
Definition: OdometryViso2.h:60
#define UERROR(...)
OdometryViso2(const rtabmap::ParametersMap &parameters=rtabmap::ParametersMap())
ULogger class and convenient macros.
const StereoCameraModel & stereoCameraModel() const
Definition: SensorData.h:216
std::vector< cv::Point2f > newCorners
Definition: OdometryInfo.h:129
RegistrationInfo reg
Definition: OdometryInfo.h:96
virtual Transform computeTransform(SensorData &image, const Transform &guess=Transform(), OdometryInfo *info=0)
Transform inverse() const
Definition: Transform.cpp:178
const Transform & localTransform() const
cv::Mat depthRaw() const
Definition: SensorData.h:189
#define UINFO(...)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:59