Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "rtabmap/core/OdometryDVO.h"
00029 #include "rtabmap/core/OdometryInfo.h"
00030 #include "rtabmap/core/util2d.h"
00031 #include "rtabmap/utilite/ULogger.h"
00032 #include "rtabmap/utilite/UTimer.h"
00033 #include "rtabmap/utilite/UStl.h"
00034
00035 #ifdef RTABMAP_DVO
00036 #include <dvo/dense_tracking.h>
00037 #include <dvo/core/surface_pyramid.h>
00038 #include <dvo/core/rgbd_image.h>
00039 #endif
00040
00041 namespace rtabmap {
00042
00043 OdometryDVO::OdometryDVO(const ParametersMap & parameters) :
00044 Odometry(parameters),
00045 #ifdef RTABMAP_DVO
00046 dvo_(0),
00047 reference_(0),
00048 camera_(0),
00049 lost_(false),
00050 #endif
00051 motionFromKeyFrame_(Transform::getIdentity())
00052 {
00053 }
00054
00055 OdometryDVO::~OdometryDVO()
00056 {
00057 #ifdef RTABMAP_DVO
00058 delete dvo_;
00059 delete reference_;
00060 delete camera_;
00061 #endif
00062 }
00063
00064 void OdometryDVO::reset(const Transform & initialPose)
00065 {
00066 Odometry::reset(initialPose);
00067 #ifdef RTABMAP_DVO
00068 if(dvo_)
00069 {
00070 delete dvo_;
00071 dvo_ = 0;
00072 }
00073 if(reference_)
00074 {
00075 delete reference_;
00076 reference_ = 0;
00077 }
00078 if(camera_)
00079 {
00080 delete camera_;
00081 camera_ = 0;
00082 }
00083 lost_ = false;
00084 motionFromKeyFrame_.setIdentity();
00085 previousLocalTransform_.setNull();
00086 #endif
00087 }
00088
00089
00090 Transform OdometryDVO::computeTransform(
00091 SensorData & data,
00092 const Transform & guess,
00093 OdometryInfo * info)
00094 {
00095 Transform t;
00096
00097 #ifdef RTABMAP_DVO
00098 UTimer timer;
00099
00100 if(data.imageRaw().empty() ||
00101 data.imageRaw().rows != data.depthOrRightRaw().rows ||
00102 data.imageRaw().cols != data.depthOrRightRaw().cols)
00103 {
00104 UERROR("Not supported input!");
00105 return t;
00106 }
00107
00108 if(!(data.cameraModels().size() == 1 && data.cameraModels()[0].isValidForReprojection()))
00109 {
00110 UERROR("Invalid camera model! Only single RGB-D camera supported by DVO. Try another odometry approach.");
00111 return t;
00112 }
00113
00114 if(dvo_ == 0)
00115 {
00116 dvo::DenseTracker::Config cfg = dvo::DenseTracker::getDefaultConfig();
00117
00118 dvo_ = new dvo::DenseTracker(cfg);
00119 }
00120
00121 cv::Mat grey, grey_s16, depth_inpainted, depth_mask, depth_mono, depth_float;
00122 if(data.imageRaw().type() != CV_32FC1)
00123 {
00124 if(data.imageRaw().type() == CV_8UC3)
00125 {
00126 cv::cvtColor(data.imageRaw(), grey, CV_BGR2GRAY);
00127 }
00128 else
00129 {
00130 grey = data.imageRaw();
00131 }
00132
00133 grey.convertTo(grey_s16, CV_32F);
00134 }
00135 else
00136 {
00137 grey_s16 = data.imageRaw();
00138 }
00139
00140
00141 if(data.depthRaw().type() == CV_32FC1)
00142 {
00143 depth_float = data.depthRaw();
00144 for(int i=0; i<depth_float.rows; ++i)
00145 {
00146 for(int j=0; j<depth_float.cols; ++j)
00147 {
00148 float & d = depth_float.at<float>(i,j);
00149 if(d == 0.0f)
00150 {
00151 d = NAN;
00152 }
00153 }
00154 }
00155 }
00156 else if(data.depthRaw().type() == CV_16UC1)
00157 {
00158 depth_float = cv::Mat(data.depthRaw().size(), CV_32FC1);
00159 for(int i=0; i<data.depthRaw().rows; ++i)
00160 {
00161 for(int j=0; j<data.depthRaw().cols; ++j)
00162 {
00163 float d = float(data.depthRaw().at<unsigned short>(i,j))/1000.0f;
00164 depth_float.at<float>(i, j) = d==0.0f?NAN:d;
00165 }
00166 }
00167 }
00168 else
00169 {
00170 UFATAL("Unknown depth format!");
00171 }
00172
00173 if(camera_ == 0)
00174 {
00175 dvo::core::IntrinsicMatrix intrinsics = dvo::core::IntrinsicMatrix::create(
00176 data.cameraModels()[0].fx(),
00177 data.cameraModels()[0].fy(),
00178 data.cameraModels()[0].cx(),
00179 data.cameraModels()[0].cy());
00180 camera_ = new dvo::core::RgbdCameraPyramid(
00181 data.cameraModels()[0].imageWidth(),
00182 data.cameraModels()[0].imageHeight(),
00183 intrinsics);
00184 }
00185
00186 dvo::core::RgbdImagePyramid * current = new dvo::core::RgbdImagePyramid(*camera_, grey_s16, depth_float);
00187
00188 const Transform & localTransform = data.cameraModels()[0].localTransform();
00189 cv::Mat covariance;
00190 if(reference_ == 0)
00191 {
00192 reference_ = current;
00193 if(!lost_)
00194 {
00195 t.setIdentity();
00196 }
00197 covariance = cv::Mat::eye(6,6,CV_64FC1) * 9999.0;
00198 }
00199 else
00200 {
00201 dvo::DenseTracker::Result result;
00202 dvo_->match(*reference_, *current, result);
00203 t = Transform::fromEigen3d(result.Transformation);
00204
00205 if(result.Information(0,0) > 0.0 && result.Information(0,0) != 1.0)
00206 {
00207 lost_ = false;
00208 cv::Mat information = cv::Mat::eye(6,6, CV_64FC1);
00209 memcpy(information.data, result.Information.data(), 36*sizeof(double));
00210
00211 covariance = cv::Mat::eye(6,6,CV_64FC1);
00212 covariance = information.inv().mul(covariance);
00213
00214
00215 Transform currentMotion = t;
00216 t = motionFromKeyFrame_.inverse() * t;
00217
00218
00219 if(currentMotion.getNorm() > 0.01 || currentMotion.getAngle() > 0.01)
00220 {
00221 if(info)
00222 {
00223 info->keyFrameAdded = true;
00224 }
00225
00226 delete reference_;
00227 reference_ = current;
00228 motionFromKeyFrame_.setIdentity();
00229 }
00230 else
00231 {
00232 delete current;
00233 motionFromKeyFrame_ = currentMotion;
00234 }
00235 }
00236 else
00237 {
00238 lost_ = true;
00239 delete reference_;
00240 delete current;
00241 reference_ = 0;
00242 motionFromKeyFrame_.setIdentity();
00243 t.setNull();
00244 previousLocalTransform_.setNull();
00245 covariance = cv::Mat::eye(6,6,CV_64FC1) * 9999.0;
00246 UWARN("dvo failed to estimate motion, tracking will be reinitialized on next frame.");
00247 }
00248
00249 if(!t.isNull() && !t.isIdentity() && !localTransform.isIdentity() && !localTransform.isNull())
00250 {
00251
00252 if(!previousLocalTransform_.isNull())
00253 {
00254 t = previousLocalTransform_ * t * localTransform.inverse();
00255 }
00256 else
00257 {
00258 t = localTransform * t * localTransform.inverse();
00259 }
00260 previousLocalTransform_ = localTransform;
00261 }
00262 }
00263
00264 if(info)
00265 {
00266 info->type = (int)kTypeDVO;
00267 info->reg.covariance = covariance;
00268 }
00269
00270 UINFO("Odom update time = %fs", timer.elapsed());
00271
00272 #else
00273 UERROR("RTAB-Map is not built with DVO support! Select another visual odometry approach.");
00274 #endif
00275 return t;
00276 }
00277
00278 }