OdometryVINS.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 
32 #include "rtabmap/utilite/UTimer.h"
33 #include "rtabmap/utilite/UStl.h"
36 #include <opencv2/imgproc/types_c.h>
37 
38 #ifdef RTABMAP_VINS
39 #include <estimator/estimator.h>
40 #include <estimator/parameters.h>
41 #include <camodocal/camera_models/PinholeCamera.h>
42 #include <camodocal/camera_models/EquidistantCamera.h>
43 #include <utility/visualization.h>
44 #endif
45 
46 namespace rtabmap {
47 
48 #ifdef RTABMAP_VINS
49 class VinsEstimator: public Estimator
50 {
51 public:
52  VinsEstimator(
53  const Transform & imuLocalTransform,
54  const StereoCameraModel & model,
55  bool rectified) : Estimator()
56  {
57  MULTIPLE_THREAD = 0;
58  setParameter();
59 
60  //overwrite camera calibration only if received model is radtan, otherwise use config
61  UASSERT(NUM_OF_CAM >= 1 && NUM_OF_CAM <=2);
62 
63  if( (NUM_OF_CAM == 2 && model.left().D_raw().cols == 4 && model.right().D_raw().cols == 4) ||
64  (NUM_OF_CAM == 1 && model.left().D_raw().cols == 4))
65  {
66  UWARN("Overwriting VINS camera calibration config with received pinhole model... rectified=%d", rectified?1:0);
67  featureTracker.m_camera.clear();
68 
69  camodocal::PinholeCameraPtr camera( new camodocal::PinholeCamera );
70  camodocal::PinholeCamera::Parameters params(
71  model.name(),
72  model.left().imageWidth(), model.left().imageHeight(),
73  rectified?0:model.left().D_raw().at<double>(0,0),
74  rectified?0:model.left().D_raw().at<double>(0,1),
75  rectified?0:model.left().D_raw().at<double>(0,2),
76  rectified?0:model.left().D_raw().at<double>(0,3),
77  rectified?model.left().fx():model.left().K_raw().at<double>(0,0),
78  rectified?model.left().fy():model.left().K_raw().at<double>(1,1),
79  rectified?model.left().cx():model.left().K_raw().at<double>(0,2),
80  rectified?model.left().cy():model.left().K_raw().at<double>(1,2));
81  camera->setParameters(params);
82  featureTracker.m_camera.push_back(camera);
83 
84  if(NUM_OF_CAM == 2)
85  {
86  camodocal::PinholeCameraPtr camera( new camodocal::PinholeCamera );
87  camodocal::PinholeCamera::Parameters params(
88  model.name(),
89  model.right().imageWidth(), model.right().imageHeight(),
90  rectified?0:model.right().D_raw().at<double>(0,0),
91  rectified?0:model.right().D_raw().at<double>(0,1),
92  rectified?0:model.right().D_raw().at<double>(0,2),
93  rectified?0:model.right().D_raw().at<double>(0,3),
94  rectified?model.right().fx():model.right().K_raw().at<double>(0,0),
95  rectified?model.right().fy():model.right().K_raw().at<double>(1,1),
96  rectified?model.right().cx():model.right().K_raw().at<double>(0,2),
97  rectified?model.right().cy():model.right().K_raw().at<double>(1,2));
98  camera->setParameters(params);
99  featureTracker.m_camera.push_back(camera);
100  }
101  }
102  else if(rectified)
103  {
104  UWARN("Images are rectified but received calibration cannot be "
105  "used, make sure calibration in config file doesn't have "
106  "distortion or send raw images to VINS odometry.");
107  if(!featureTracker.m_camera.empty())
108  {
109  if(featureTracker.m_camera.front()->imageWidth() != model.left().imageWidth() ||
110  featureTracker.m_camera.front()->imageHeight() != model.left().imageHeight())
111  {
112  UERROR("Received images don't have same size (%dx%d) than in the config file (%dx%d)!",
113  model.left().imageWidth(),
114  model.left().imageHeight(),
115  featureTracker.m_camera.front()->imageWidth(),
116  featureTracker.m_camera.front()->imageHeight());
117  }
118  }
119  }
120 
121  Transform imuCam0 = imuLocalTransform.inverse() * model.localTransform();
122 
123  tic[0] = Vector3d(imuCam0.x(), imuCam0.y(), imuCam0.z());
124  ric[0] = imuCam0.toEigen4d().block<3,3>(0,0);
125 
126  if(NUM_OF_CAM == 2)
127  {
128  Transform cam0cam1;
129  if(rectified)
130  {
131  cam0cam1 = Transform(
132  1, 0, 0, model.baseline(),
133  0, 1, 0, 0,
134  0, 0, 1, 0);
135  }
136  else
137  {
138  cam0cam1 = model.stereoTransform().inverse();
139  }
140  UASSERT(!cam0cam1.isNull());
141  Transform imuCam1 = imuCam0 * cam0cam1;
142 
143  tic[1] = Vector3d(imuCam1.x(), imuCam1.y(), imuCam1.z());
144  ric[1] = imuCam1.toEigen4d().block<3,3>(0,0);
145  }
146 
147  for (int i = 0; i < NUM_OF_CAM; i++)
148  {
149  cout << " exitrinsic cam " << i << endl << ric[i] << endl << tic[i].transpose() << endl;
150  }
151  f_manager.setRic(ric);
152  ProjectionTwoFrameOneCamFactor::sqrt_info = FOCAL_LENGTH / 1.5 * Matrix2d::Identity();
153  ProjectionTwoFrameTwoCamFactor::sqrt_info = FOCAL_LENGTH / 1.5 * Matrix2d::Identity();
154  ProjectionOneFrameTwoCamFactor::sqrt_info = FOCAL_LENGTH / 1.5 * Matrix2d::Identity();
155  td = TD;
156  g = G;
157  cout << "set g " << g.transpose() << endl;
158  }
159 
160  // Copy of original inputImage() so that overridden processMeasurements() is used and threading is disabled.
161  void inputImage(double t, const cv::Mat &_img, const cv::Mat &_img1)
162  {
163  inputImageCnt++;
164  map<int, vector<pair<int, Eigen::Matrix<double, 7, 1>>>> featureFrame;
165  TicToc featureTrackerTime;
166  if(_img1.empty())
167  featureFrame = featureTracker.trackImage(t, _img);
168  else
169  featureFrame = featureTracker.trackImage(t, _img, _img1);
170  //printf("featureTracker time: %f\n", featureTrackerTime.toc());
171 
172  //if(MULTIPLE_THREAD)
173  //{
174  // if(inputImageCnt % 2 == 0)
175  // {
176  // mBuf.lock();
177  // featureBuf.push(make_pair(t, featureFrame));
178  // mBuf.unlock();
179  // }
180  //}
181  //else
182  {
183  mBuf.lock();
184  featureBuf.push(make_pair(t, featureFrame));
185  mBuf.unlock();
186  TicToc processTime;
187  processMeasurements();
188  UDEBUG("VINS process time: %f", processTime.toc());
189  }
190 
191  }
192 
193  // Copy of original inputIMU() but with publisher commented
194  void inputIMU(double t, const Vector3d &linearAcceleration, const Vector3d &angularVelocity)
195  {
196  mBuf.lock();
197  accBuf.push(make_pair(t, linearAcceleration));
198  gyrBuf.push(make_pair(t, angularVelocity));
199  //printf("input imu with time %f \n", t);
200  mBuf.unlock();
201 
202  fastPredictIMU(t, linearAcceleration, angularVelocity);
203  //if (solver_flag == NON_LINEAR)
204  // pubLatestOdometry(latest_P, latest_Q, latest_V, t);
205  }
206 
207  // Copy of original processMeasurements() but with publishers commented and threading disabled
208  void processMeasurements()
209  {
210  //while (1)
211  {
212  //printf("process measurments\n");
213  pair<double, map<int, vector<pair<int, Eigen::Matrix<double, 7, 1> > > > > feature;
214  vector<pair<double, Eigen::Vector3d>> accVector, gyrVector;
215  if(!featureBuf.empty())
216  {
217  feature = featureBuf.front();
218  curTime = feature.first + td;
219  //while(1)
220  //{
221  if (!((!USE_IMU || IMUAvailable(feature.first + td))))
222  //if ((!USE_IMU || IMUAvailable(feature.first + td)))
223  // break;
224  //else
225  {
226  printf("wait for imu ... \n");
227  //if (! MULTIPLE_THREAD)
228  return;
229  //std::chrono::milliseconds dura(5);
230  //std::this_thread::sleep_for(dura);
231  }
232  //}
233  mBuf.lock();
234  if(USE_IMU)
235  getIMUInterval(prevTime, curTime, accVector, gyrVector);
236 
237  featureBuf.pop();
238  mBuf.unlock();
239 
240  if(USE_IMU)
241  {
242  if(!initFirstPoseFlag)
243  initFirstIMUPose(accVector);
244  UDEBUG("accVector.size() = %d", accVector.size());
245  for(size_t i = 0; i < accVector.size(); i++)
246  {
247  double dt;
248  if(i == 0)
249  dt = accVector[i].first - prevTime;
250  else if (i == accVector.size() - 1)
251  dt = curTime - accVector[i - 1].first;
252  else
253  dt = accVector[i].first - accVector[i - 1].first;
254  processIMU(accVector[i].first, dt, accVector[i].second, gyrVector[i].second);
255  }
256  }
257 
258  processImage(feature.second, feature.first);
259 
260  prevTime = curTime;
261 
262  printStatistics(*this, 0);
263 
264  //std_msgs::Header header;
265  //header.frame_id = "world";
266  //header.stamp = ros::Time(feature.first);
267 
268  //pubOdometry(*this, header);
269  //pubKeyPoses(*this, header);
270  //pubCameraPose(*this, header);
271  //pubPointCloud(*this, header);
272  //pubKeyframe(*this);
273  //pubTF(*this, header);
274  }
275 
276  //if (! MULTIPLE_THREAD)
277  // break;
278 
279  //std::chrono::milliseconds dura(2);
280  //std::this_thread::sleep_for(dura);
281  }
282  }
283 };
284 #endif
285 
287  Odometry(parameters)
288 #ifdef RTABMAP_VINS
289  ,
290  vinsEstimator_(0),
291  imagesProcessed_(0),
292  initGravity_(false),
293  previousPose_(Transform::getIdentity())
294 #endif
295 {
296 #ifdef RTABMAP_VINS
297  // intialize
298  std::string configFilename;
299  Parameters::parse(parameters, Parameters::kOdomVINSConfigPath(), configFilename);
300  if(configFilename.empty())
301  {
302  UERROR("VINS config file is empty (%s=%s)!",
303  Parameters::kOdomVINSConfigPath().c_str(),
304  Parameters::kOdomVINSConfigPath().c_str());
305  }
306  else
307  {
308  readParameters(uReplaceChar(configFilename, '~', UDirectory::homeDir()));
309  }
310 #endif
311 }
312 
314 {
315 #ifdef RTABMAP_VINS
316  delete vinsEstimator_;
317 #endif
318 }
319 
320 void OdometryVINS::reset(const Transform & initialPose)
321 {
322  Odometry::reset(initialPose);
323 #ifdef RTABMAP_VINS
324  if(!initGravity_)
325  {
326  delete vinsEstimator_;
327  vinsEstimator_ = 0;
328  previousPose_.setIdentity();
329  lastImu_ = IMU();
330  previousLocalTransform_.setNull();
331  }
332  initGravity_ = false;
333 #endif
334 }
335 
336 // return not null transform if odometry is correctly computed
338  SensorData & data,
339  const Transform & guess,
340  OdometryInfo * info)
341 {
342  Transform t;
343 #ifdef RTABMAP_VINS
344  UTimer timer;
345 
346  if(USE_IMU!=0 && !data.imu().empty())
347  {
348  double t = data.stamp();
349  double dx = data.imu().linearAcceleration().val[0];
350  double dy = data.imu().linearAcceleration().val[1];
351  double dz = data.imu().linearAcceleration().val[2];
352  double rx = data.imu().angularVelocity().val[0];
353  double ry = data.imu().angularVelocity().val[1];
354  double rz = data.imu().angularVelocity().val[2];
355  Vector3d acc(dx, dy, dz);
356  Vector3d gyr(rx, ry, rz);
357 
358  UDEBUG("IMU update stamp=%f", data.stamp());
359 
360  if(vinsEstimator_ != 0)
361  {
362  vinsEstimator_->inputIMU(t, acc, gyr);
363  }
364  else
365  {
366  lastImu_ = data.imu();
367  UWARN("Waiting an image for initialization...");
368  }
369  }
370 
371  if(!data.imageRaw().empty() && !data.rightRaw().empty())
372  {
373  if(USE_IMU==1 && lastImu_.localTransform().isNull())
374  {
375  UWARN("Waiting IMU for initialization...");
376  return t;
377  }
378  if(vinsEstimator_ == 0)
379  {
380  // intialize
381  vinsEstimator_ = new VinsEstimator(
382  lastImu_.localTransform().isNull()?Transform::getIdentity():lastImu_.localTransform(),
383  data.stereoCameraModel(),
384  this->imagesAlreadyRectified());
385  }
386 
387  UDEBUG("Image update stamp=%f", data.stamp());
388  cv::Mat left;
389  cv::Mat right;
390  if(data.imageRaw().type() == CV_8UC3)
391  {
392  cv::cvtColor(data.imageRaw(), left, CV_BGR2GRAY);
393  }
394  else if(data.imageRaw().type() == CV_8UC1)
395  {
396  left = data.imageRaw().clone();
397  }
398  else
399  {
400  UFATAL("Not supported color type!");
401  }
402  if(data.rightRaw().type() == CV_8UC3)
403  {
404  cv::cvtColor(data.rightRaw(), right, CV_BGR2GRAY);
405  }
406  else if(data.rightRaw().type() == CV_8UC1)
407  {
408  right = data.rightRaw().clone();
409  }
410  else
411  {
412  UFATAL("Not supported color type!");
413  }
414 
415  vinsEstimator_->inputImage(data.stamp(), left, right);
416 
417  if(vinsEstimator_->solver_flag == Estimator::NON_LINEAR)
418  {
419  Quaterniond tmp_Q;
420  tmp_Q = Quaterniond(vinsEstimator_->Rs[WINDOW_SIZE]);
421  Transform p(
422  vinsEstimator_->Ps[WINDOW_SIZE].x(),
423  vinsEstimator_->Ps[WINDOW_SIZE].y(),
424  vinsEstimator_->Ps[WINDOW_SIZE].z(),
425  tmp_Q.x(),
426  tmp_Q.y(),
427  tmp_Q.z(),
428  tmp_Q.w());
429 
430  if(!p.isNull())
431  {
432  if(!lastImu_.localTransform().isNull())
433  {
434  p = Transform(0,1,0,0,-1,0,0,0, 0,0,1,0) * p * lastImu_.localTransform().inverse();
435  }
436 
437  if(this->getPose().rotation().isIdentity())
438  {
439  initGravity_ = true;
440  this->reset(this->getPose()*p.rotation());
441  }
442 
443  if(previousPose_.isIdentity())
444  {
445  previousPose_ = p;
446  }
447 
448  // make it incremental
449  Transform previousPoseInv = previousPose_.inverse();
450  t = previousPoseInv*p;
451  previousPose_ = p;
452 
453  if(info)
454  {
455  info->type = this->getType();
456  info->reg.covariance = cv::Mat::eye(6,6, CV_64FC1);
457  info->reg.covariance *= this->framesProcessed() == 0?9999:0.0001;
458 
459  // feature map
460  Transform fixT = this->getPose()*previousPoseInv*Transform(0,1,0,0,-1,0,0,0, 0,0,1,0);
461  for (auto &it_per_id : vinsEstimator_->f_manager.feature)
462  {
463  int used_num;
464  used_num = it_per_id.feature_per_frame.size();
465  if (!(used_num >= 2 && it_per_id.start_frame < WINDOW_SIZE - 2))
466  continue;
467  if (it_per_id.start_frame > WINDOW_SIZE * 3.0 / 4.0 || it_per_id.solve_flag != 1)
468  continue;
469  int imu_i = it_per_id.start_frame;
470  Vector3d pts_i = it_per_id.feature_per_frame[0].point * it_per_id.estimated_depth;
471  Vector3d w_pts_i = vinsEstimator_->Rs[imu_i] * (vinsEstimator_->ric[0] * pts_i + vinsEstimator_->tic[0]) + vinsEstimator_->Ps[imu_i];
472 
473  cv::Point3f p;
474  p.x = w_pts_i(0);
475  p.y = w_pts_i(1);
476  p.z = w_pts_i(2);
477  p = util3d::transformPoint(p, fixT);
478  info->localMap.insert(std::make_pair(it_per_id.feature_id, p));
479 
480  if(this->imagesAlreadyRectified())
481  {
482  cv::Point2f pt;
483  data.stereoCameraModel().left().reproject(pts_i(0), pts_i(1), pts_i(2), pt.x, pt.y);
484  info->reg.inliersIDs.push_back(info->newCorners.size());
485  info->newCorners.push_back(pt);
486  }
487  }
488  info->features = info->newCorners.size();
489  info->localMapSize = info->localMap.size();
490  }
491  UINFO("Odom update time = %fs p=%s", timer.elapsed(), p.prettyPrint().c_str());
492  }
493  }
494  else
495  {
496  UWARN("VINS not yet initialized... waiting to get enough IMU messages");
497  }
498  }
499  else if(!data.imageRaw().empty() && !data.depthRaw().empty())
500  {
501  UERROR("VINS-Fusion doesn't work with RGB-D data, stereo images are required!");
502  }
503  else if(!data.imageRaw().empty() && data.depthOrRightRaw().empty())
504  {
505  UERROR("VINS-Fusion requires stereo images!");
506  }
507 #else
508  UERROR("RTAB-Map is not built with VINS support! Select another visual odometry approach.");
509 #endif
510  return t;
511 }
512 
513 } // namespace rtabmap
static std::string homeDir()
Definition: UDirectory.cpp:355
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:476
unsigned int framesProcessed() const
Definition: Odometry.h:78
Definition: UTimer.h:46
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
bool empty() const
Definition: IMU.h:63
double elapsed()
Definition: UTimer.h:75
bool imagesAlreadyRectified() const
Definition: Odometry.h:79
virtual void reset(const Transform &initialPose=Transform::getIdentity())
Definition: Odometry.cpp:191
std::map< int, cv::Point3f > localMap
Definition: OdometryInfo.h:124
Transform rotation() const
Definition: Transform.cpp:195
static Transform getIdentity()
Definition: Transform.cpp:380
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
const Transform & getPose() const
Definition: Odometry.h:73
std::vector< int > inliersIDs
virtual Transform computeTransform(SensorData &image, const Transform &guess=Transform(), OdometryInfo *info=0)
const cv::Mat & imageRaw() const
Definition: SensorData.h:164
virtual Odometry::Type getType()
Definition: OdometryVINS.h:44
#define UFATAL(...)
virtual void reset(const Transform &initialPose=Transform::getIdentity())
cv::Mat rightRaw() const
Definition: SensorData.h:190
#define UASSERT(condition)
Wrappers of STL for convenient functions.
const CameraModel & left() const
const cv::Vec3d linearAcceleration() const
Definition: IMU.h:58
void reproject(float x, float y, float z, float &u, float &v) const
std::string UTILITE_EXP uReplaceChar(const std::string &str, char before, char after)
Definition: UConversion.cpp:32
const cv::Mat & depthOrRightRaw() const
Definition: SensorData.h:165
double stamp() const
Definition: SensorData.h:157
GLM_FUNC_DECL detail::tquat< T, P > rotation(detail::tvec3< T, P > const &orig, detail::tvec3< T, P > const &dest)
GLM_FUNC_DECL bool isIdentity(matType< T, P > const &m, T const &epsilon)
#define false
Definition: ConvertUTF.c:56
const IMU & imu() const
Definition: SensorData.h:269
#define UDEBUG(...)
#define UERROR(...)
ULogger class and convenient macros.
const StereoCameraModel & stereoCameraModel() const
Definition: SensorData.h:216
#define UWARN(...)
OdometryVINS(const rtabmap::ParametersMap &parameters=rtabmap::ParametersMap())
std::vector< cv::Point2f > newCorners
Definition: OdometryInfo.h:129
RegistrationInfo reg
Definition: OdometryInfo.h:96
Transform inverse() const
Definition: Transform.cpp:178
cv::Mat depthRaw() const
Definition: SensorData.h:189
const cv::Vec3d & angularVelocity() const
Definition: IMU.h:55
#define UINFO(...)


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