45 #include <opencv2/imgproc/imgproc.hpp>    46 #include <opencv2/calib3d/calib3d.hpp>    47 #include <opencv2/video/tracking.hpp>    48 #include <pcl/common/centroid.h>    54         flowWinSize_(
Parameters::defaultVisCorFlowWinSize()),
    55         flowIterations_(
Parameters::defaultVisCorFlowIterations()),
    57         flowMaxLevel_(
Parameters::defaultVisCorFlowMaxLevel()),
    58         minInliers_(
Parameters::defaultVisMinInliers()),
    59         iterations_(
Parameters::defaultVisIterations()),
    60         pnpReprojError_(
Parameters::defaultVisPnPReprojError()),
    62         pnpRefineIterations_(
Parameters::defaultVisPnPRefineIterations()),
    63         localHistoryMaxSize_(
Parameters::defaultOdomF2MMaxSize()),
    64         initMinFlow_(
Parameters::defaultOdomMonoInitMinFlow()),
    65         initMinTranslation_(
Parameters::defaultOdomMonoInitMinTranslation()),
    66         minTranslation_(
Parameters::defaultOdomMonoMinTranslation()),
    67         fundMatrixReprojError_(
Parameters::defaultVhEpRansacParam1()),
    68         fundMatrixConfidence_(
Parameters::defaultVhEpRansacParam2()),
    69         maxVariance_(
Parameters::defaultOdomMonoMaxVariance()),
    95         std::string roi = Parameters::defaultVisRoiRatios();
    97         customParameters.insert(
ParametersPair(Parameters::kMemDepthAsMask(), 
"false"));
    98         customParameters.insert(
ParametersPair(Parameters::kKpRoiRatios(), roi));
    99         customParameters.insert(
ParametersPair(Parameters::kMemRehearsalSimilarity(), 
"1.0")); 
   100         customParameters.insert(
ParametersPair(Parameters::kMemBinDataKept(), 
"false"));
   101         customParameters.insert(
ParametersPair(Parameters::kMemSTMSize(), 
"0"));
   102         customParameters.insert(
ParametersPair(Parameters::kMemNotLinkedNodesKept(), 
"false"));
   103         customParameters.insert(
ParametersPair(Parameters::kKpTfIdfLikelihoodUsed(), 
"false"));
   104         int nn = Parameters::defaultVisCorNNType();
   105         float nndr = Parameters::defaultVisCorNNDR();
   106         int featureType = Parameters::defaultVisFeatureType();
   107         int maxFeatures = Parameters::defaultVisMaxFeatures();
   117         int subPixWinSize = Parameters::defaultVisSubPixWinSize();
   118         int subPixIterations = Parameters::defaultVisSubPixIterations();
   119         double subPixEps = Parameters::defaultVisSubPixEps();
   121         Parameters::parse(parameters, Parameters::kVisSubPixIterations(), subPixIterations);
   128         for(ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
   132                         customParameters.insert(*iter);
   139                 UERROR(
"Error initializing the memory for Mono Odometry.");
   169                 UERROR(
"Image empty! Cannot compute odometry...");
   176                 UERROR(
"Odometry cannot be done without calibration or on multi-camera!");
   198         std::vector<CameraModel> newModel;
   199         newModel.push_back(cameraModel);
   204         int correspondences = 0;
   211                 cv::cvtColor(data.
imageRaw(), newFrame, cv::COLOR_BGR2GRAY);
   237                         bool newPtsAdded = 
false;
   240                         nFeatures = (int)newS->
getWords().size();
   243                                 cv::Mat K = cameraModel.
K();
   245                                 cv::Mat R = (cv::Mat_<double>(3,3) <<
   246                                                 (
double)pnpGuess.
r11(), (double)pnpGuess.
r12(), (double)pnpGuess.
r13(),
   247                                                 (double)pnpGuess.
r21(), (double)pnpGuess.
r22(), (double)pnpGuess.
r23(),
   248                                                 (double)pnpGuess.
r31(), (double)pnpGuess.
r32(), (double)pnpGuess.
r33());
   249                                 cv::Mat rvec(1,3, CV_64FC1);
   250                                 cv::Rodrigues(R, rvec);
   251                                 cv::Mat tvec = (cv::Mat_<double>(1,3) << (
double)pnpGuess.
x(), (double)pnpGuess.
y(), (double)pnpGuess.
z());
   253                                 std::vector<cv::Point3f> objectPoints;
   254                                 std::vector<cv::Point2f> imagePoints;
   257                                 UDEBUG(
"compute PnP from optical flow");
   263                                 UDEBUG(
"project points to previous image");
   264                                 std::vector<cv::Point2f> prevImagePoints;
   267                                 cv::Mat prevR = (cv::Mat_<double>(3,3) <<
   268                                                 (
double)prevGuess.
r11(), (double)prevGuess.
r12(), (double)prevGuess.
r13(),
   269                                                 (double)prevGuess.
r21(), (double)prevGuess.
r22(), (double)prevGuess.
r23(),
   270                                                 (double)prevGuess.
r31(), (double)prevGuess.
r32(), (double)prevGuess.
r33());
   271                                 cv::Mat prevRvec(1,3, CV_64FC1);
   272                                 cv::Rodrigues(prevR, prevRvec);
   273                                 cv::Mat prevTvec = (cv::Mat_<double>(1,3) << (
double)prevGuess.
x(), (double)prevGuess.
y(), (double)prevGuess.
z());
   274                                 cv::projectPoints(objectPoints, prevRvec, prevTvec, K, cv::Mat(), prevImagePoints);
   277                                 UDEBUG(
"project points to current image");
   278                                 cv::projectPoints(objectPoints, rvec, tvec, K, cv::Mat(), imagePoints);
   281                                 std::vector<cv::Point3f> objectPointsTmp(objectPoints.size());
   282                                 std::vector<cv::Point2f> refCorners(objectPoints.size());
   283                                 std::vector<cv::Point2f> newCorners(objectPoints.size());
   284                                 matches.resize(objectPoints.size());
   286                                 for(
unsigned int i=0; i<objectPoints.size(); ++i)
   293                                                 refCorners[oi] = prevImagePoints[i];
   294                                                 newCorners[oi] = imagePoints[i];
   308                                                 objectPointsTmp[oi] = objectPoints[i];
   309                                                 matches[oi] = ids[i];
   313                                 objectPointsTmp.resize(oi);
   314                                 refCorners.resize(oi);
   315                                 newCorners.resize(oi);
   319                                 std::vector<unsigned char> statusFlowInliers;
   320                                 std::vector<float> err;
   321                                 UDEBUG(
"cv::calcOpticalFlowPyrLK() begin");
   322                                 cv::calcOpticalFlowPyrLK(
   331                                                 cv::OPTFLOW_LK_GET_MIN_EIGENVALS | cv::OPTFLOW_USE_INITIAL_FLOW, 1
e-4);
   332                                 UDEBUG(
"cv::calcOpticalFlowPyrLK() end");
   334                                 objectPoints.resize(statusFlowInliers.size());
   335                                 imagePoints.resize(statusFlowInliers.size());
   336                                 std::vector<int> matchesTmp(statusFlowInliers.size());
   338                                 for(
unsigned int i=0; i<statusFlowInliers.size(); ++i)
   340                                         if(statusFlowInliers[i] &&
   344                                                 objectPoints[oi] = objectPointsTmp[i];
   345                                                 imagePoints[oi] = newCorners[i];
   346                                                 matchesTmp[oi] = matches[i];
   356                                                         kpt.pt = newCorners[i];
   357                                                         info->
words.insert(std::make_pair(matches[i], kpt));
   361                                 UDEBUG(
"Flow inliers= %d/%d", oi, (
int)statusFlowInliers.size());
   362                                 objectPoints.resize(oi);
   363                                 imagePoints.resize(oi);
   364                                 matchesTmp.resize(oi);
   365                                 matches = matchesTmp;
   371                                 correspondences = (int)matches.size();
   380                                         std::vector<int> inliersV;
   396                                         UDEBUG(
"inliers=%d/%d", (
int)inliersV.size(), (int)objectPoints.size());
   398                                         inliers = (int)inliersV.size();
   401                                                 UWARN(
"PnP not enough inliers (%d < %d), rejecting the transform...", (
int)inliersV.size(), 
minInliers_);
   405                                                 cv::Mat R(3,3,CV_64FC1);
   406                                                 cv::Rodrigues(rvec, R);
   407                                                 Transform pnp = 
Transform(R.at<
double>(0,0), R.at<
double>(0,1), R.at<
double>(0,2), tvec.at<
double>(0),
   408                                                                                                   R.at<
double>(1,0), R.at<
double>(1,1), R.at<
double>(1,2), tvec.at<
double>(1),
   409                                                                                                   R.at<
double>(2,0), R.at<
double>(2,1), R.at<
double>(2,2), tvec.at<
double>(2));
   415                                                         for(
unsigned int i=0; i<inliersV.size(); ++i)
   422                                                 cv::Mat covariance = cv::Mat::eye(6, 6, CV_64FC1);
   423                                                 std::vector<cv::Point2f> imagePointsReproj;
   424                                                 cv::projectPoints(objectPoints, rvec, tvec, K, cv::Mat(), imagePointsReproj);
   426                                                 for(
unsigned int i=0; i<inliersV.size(); ++i)
   428                                                         err += 
uNormSquared(imagePoints.at(inliersV[i]).x - imagePointsReproj.at(inliersV[i]).x, imagePoints.at(inliersV[i]).y - imagePointsReproj.at(inliersV[i]).y);
   431                                                 covariance *= 
std::sqrt(err/
float(inliersV.size()));
   438                                                 poses.insert(std::make_pair(newS->
id(), this->
getPose()*output));
   441                                                         UWARN(
"Bundle adjustment: fill arguments");
   444                                                         links.insert(std::make_pair(
keyFramePoses_.rbegin()->first, newLink));
   445                                                         models.insert(std::make_pair(newS->
id(), newModel));
   446                                                         std::map<int, std::map<int, FeatureBA> > wordReferences;
   451                                                                 for(std::multimap<int, int>::const_iterator jter=s->
getWords().begin(); jter!=s->
getWords().end(); ++jter)
   455                                                                                 if(wordReferences.find(jter->first)==wordReferences.end())
   457                                                                                         wordReferences.insert(std::make_pair(jter->first, std::map<int, FeatureBA>()));
   465                                                                                 const cv::KeyPoint & kpts = s->
getWordsKpts()[jter->second];
   466                                                                                 wordReferences.at(jter->first).insert(std::make_pair(s->
id(), 
FeatureBA(kpts, depth, cv::Mat())));
   471                                                         std::set<int> outliers;
   472                                                         UWARN(
"Bundle adjustment begin");
   473                                                         poses = ba->optimizeBA(poses.begin()->first, poses, links, models, 
localMap_, wordReferences, &outliers);
   474                                                         UWARN(
"Bundle adjustment end");
   484                                                 stMem.erase(newS->
id());
   486                                                 int maxLikelihoodId = -1;
   487                                                 float maxLikelihood = 0;
   488                                                 for(std::map<int, float>::iterator iter=likelihood.begin(); iter!=likelihood.end(); ++iter)
   490                                                         if(iter->second > maxLikelihood)
   492                                                                 maxLikelihood = iter->second;
   493                                                                 maxLikelihoodId = iter->first;
   496                                                 if(maxLikelihoodId == -1)
   498                                                         UWARN(
"Cannot find a keyframe similar enough to generate new 3D points!");
   500                                                 else if(poses.size())
   508                                                         UINFO(
"Inliers= %d/%d (%f)", inliers, (
int)imagePoints.size(), float(inliers)/float(imagePoints.size()));
   512                                                                 UINFO(
"Translation with the nearest frame is too small (%f<%f) to add new points to local map",
   515                                                         else if(
float(inliers)/float(imagePoints.size()) < 
keyFrameThr_)
   519                                                                 std::map<int, cv::KeyPoint> wordsPrevious;
   520                                                                 std::map<int, cv::KeyPoint> wordsNew;
   521                                                                 for(std::map<int, int>::iterator iter=uniqueWordsPrevious.begin(); iter!=uniqueWordsPrevious.end(); ++iter)
   523                                                                         wordsPrevious.insert(std::make_pair(iter->first, previousS->
getWordsKpts()[iter->second]));
   525                                                                 for(std::map<int, int>::iterator iter=uniqueWordsNew.begin(); iter!=uniqueWordsNew.end(); ++iter)
   527                                                                         wordsNew.insert(std::make_pair(iter->first, newS->
getWordsKpts()[iter->second]));
   539                                                                         UWARN(
"Epipolar geometry not enough inliers (%d < %d), rejecting the transform (%s)...",
   547                                                                         std::multimap<int, cv::Point3f> wordsToAdd;
   548                                                                         for(std::map<int, cv::Point3f>::iterator iter=inliers3D.begin();
   549                                                                                 iter != inliers3D.end();
   559                                                                                         wordsToAdd.insert(std::make_pair(iter->first, newPt));
   563                                                                         if((
int)wordsToAdd.size())
   565                                                                                 localMap_.insert(wordsToAdd.begin(), wordsToAdd.end());
   567                                                                                 UWARN(
"Added %d words", (
int)wordsToAdd.size());
   573                                                                                 std::vector<cv::Point3f> newCorners3;
   576                                                                                         std::vector<cv::KeyPoint> newKeypoints(imagePoints.size());
   577                                                                                         for(
size_t i=0;i<imagePoints.size(); ++i)
   579                                                                                                 newKeypoints[i] = cv::KeyPoint(imagePoints[i], 3);
   582                                                                                         for(
size_t i=0;i<newCorners3.size(); ++i)
   585                                                                                                    inliers3D.find(matches[i])!=inliers3D.end())
   587                                                                                                         inliers3D.at(matches[i]) = newCorners3[i];
   591                                                                                                         inliers3D.erase(matches[i]);
   596                                                                                 if(!inliers3D.empty())
   598                                                                                         UDEBUG(
"Added %d/%d valid 3D features", (
int)inliers3D.size(), (int)wordsToAdd.size());
   609                                                                                         std::list<int> removedPts;
   615                                                                                         for(std::list<int>::iterator iter = removedPts.begin(); iter!=removedPts.end(); ++iter)
   653                         std::multimap<int, int>::const_iterator jter=refS->
getWords().find(iter->first);
   656                         refCornersGuess[ii] = iter->second;
   657                         cornerIds[ii] = iter->first;
   663                 std::vector<unsigned char> statusFlowInliers;
   664                 std::vector<float> err;
   665                 UDEBUG(
"cv::calcOpticalFlowPyrLK() begin");
   666                 cv::calcOpticalFlowPyrLK(
   675                                 cv::OPTFLOW_LK_GET_MIN_EIGENVALS | cv::OPTFLOW_USE_INITIAL_FLOW, 1
e-4);
   676                 UDEBUG(
"cv::calcOpticalFlowPyrLK() end");
   678                 UDEBUG(
"Filtering optical flow outliers...");
   688                 std::vector<cv::Point2f> tmpRefCorners(statusFlowInliers.size());
   689                 std::vector<cv::Point2f> newCorners(statusFlowInliers.size());
   690                 std::vector<int> inliersV(statusFlowInliers.size());
   691                 std::vector<int> tmpCornersId(statusFlowInliers.size());
   692                 UASSERT(refCornersGuess.size() == statusFlowInliers.size());
   693                 UASSERT(refCorners.size() == statusFlowInliers.size());
   694                 UASSERT(cornerIds.size() == statusFlowInliers.size());
   695                 for(
unsigned int i=0; i<statusFlowInliers.size(); ++i)
   697                         if(statusFlowInliers[i])
   699                                 float dx = refCorners[i].x - refCornersGuess[i].x;
   700                                 float dy = refCorners[i].y - refCornersGuess[i].y;
   704                                 tmpRefCorners[oi] = refCorners[i];
   705                                 newCorners[oi] = refCornersGuess[i];
   710                                 tmpCornersId[oi] = cornerIds[i];
   723                 tmpRefCorners.resize(oi);
   724                 newCorners.resize(oi);
   725                 inliersV.resize((oi));
   726                 tmpCornersId.resize(oi);
   727                 refCorners=  tmpRefCorners;
   728                 cornerIds = tmpCornersId;
   734                         inliers = (int)inliersV.size();
   737                 UDEBUG(
"Filtering optical flow outliers...done! (inliers=%d/%d)", oi, (
int)statusFlowInliers.size());
   742                         std::vector<cv::Point3f> refCorners3;
   745                                 std::vector<cv::KeyPoint> refKeypoints(refCorners.size());
   746                                 for(
size_t i=0;i<refCorners.size(); ++i)
   748                                         refKeypoints[i] = cv::KeyPoint(refCorners[i], 3);
   753                         std::map<int, cv::KeyPoint> refWords;
   754                         std::map<int, cv::KeyPoint> newWords;
   755                         std::map<int, cv::Point3f> refWords3Guess;
   756                         for(
unsigned int i=0; i<cornerIds.size(); ++i)
   758                                 refWords.insert(std::make_pair(cornerIds[i], cv::KeyPoint(refCorners[i], 3)));
   759                                 newWords.insert(std::make_pair(cornerIds[i], cv::KeyPoint(newCorners[i], 3)));
   760                                 if(!refCorners3.empty())
   762                                         refWords3Guess.insert(std::make_pair(cornerIds[i], refCorners3[i]));
   778                                 UWARN(
"Camera must be moved at least %f m for initialization (current=%f)",
   785                                 for(std::map<int, cv::Point3f>::iterator iter=refWords3.begin(); iter!=refWords3.end();)
   787                                         std::map<int, cv::Point3f>::iterator jterGuess3D = refWords3Guess.find(iter->first);
   788                                         if(jterGuess3D != refWords3Guess.end() &&
   791                                                 iter->second = jterGuess3D->second;
   796                                                 refWords3.erase(iter++);
   799                                 if(!refWords3.empty())
   801                                         UDEBUG(
"Added %d/%d valid 3D features", (
int)refWords3.size(), (int)
localMap_.size());
   810                         UWARN(
"Flow not enough high! flow=%f ki=%d", flow, oi);
   828                         const std::multimap<int, int> & words = s->
getWords();
   831                                 for(std::multimap<int, int>::const_iterator iter=words.begin(); iter!=words.end(); ++iter)
   833                                         if(words.count(iter->first) == 1)
   846                         UERROR(
"Failed creating signature");
   862         UINFO(
"Odom update=%fs tf=[%s] inliers=%d/%d, local_map[%d]=%d, accepted=%s",
   869                         !output.
isNull()?
"true":
"false");
 static bool isFeatureParameter(const std::string ¶m)
bool RTABMAP_EXP isFinite(const cv::Point3f &pt)
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
const cv::Size & imageSize() const
std::map< K, V > uMultimapToMapUnique(const std::multimap< K, V > &m)
std::vector< cv::Point2f > refCorners
int getLastSignatureId() const
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
std::vector< K > uKeys(const std::multimap< K, V > &mm)
std::map< int, cv::Point2f > firstFrameGuessCorners_
std::map< int, cv::Point3f > RTABMAP_EXP generateWords3DMono(const std::map< int, cv::KeyPoint > &kpts, const std::map< int, cv::KeyPoint > &previousKpts, const CameraModel &cameraModel, Transform &cameraTransform, float ransacReprojThreshold=3.0f, float ransacConfidence=0.99f, const std::map< int, cv::Point3f > &refGuess3D=std::map< int, cv::Point3f >(), double *variance=0, std::vector< int > *matchesOut=0)
bool uIsInBounds(const T &value, const T &low, const T &high)
const std::set< int > & getStMem() const
virtual void reset(const Transform &initialPose=Transform::getIdentity())
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
const Signature * getLastWorkingSignature() const
virtual Transform computeTransform(SensorData &data, const Transform &guess=Transform(), OdometryInfo *info=0)
std::map< int, cv::Point3f > localMap
std::pair< std::string, std::string > ParametersPair
const cv::Mat & depthOrRightRaw() const
GLM_FUNC_DECL genType e()
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
const std::vector< StereoCameraModel > & stereoCameraModels() const
std::map< std::string, std::string > ParametersMap
OdometryMono(const rtabmap::ParametersMap ¶meters=rtabmap::ParametersMap())
Basic mathematics functions. 
std::vector< int > inliersIDs
Some conversion functions. 
void deleteLocation(int locationId, std::list< int > *deletedWords=0)
float initMinTranslation_
const Signature * getSignature(int id) const
bool init(const std::string &dbUrl, bool dbOverwritten=false, const ParametersMap ¶meters=ParametersMap(), bool postInitClosingEvents=false)
bool uIsFinite(const T &value)
const std::vector< cv::KeyPoint > & getWordsKpts() const
#define UASSERT(condition)
std::vector< cv::Point3f > generateKeypoints3D(const SensorData &data, const std::vector< cv::KeyPoint > &keypoints) const
Wrappers of STL for convenient functions. 
bool isInfoDataFilled() const
const std::vector< CameraModel > & cameraModels() const
static Feature2D * create(const ParametersMap ¶meters=ParametersMap())
std::vector< int > cornerInliers
bool update(const SensorData &data, Statistics *stats=0)
const cv::Mat & imageRaw() const
const Transform & localTransform() const
void setStereoImage(const cv::Mat &left, const cv::Mat &right, const StereoCameraModel &stereoCameraModel, bool clearPreviousData=true)
bool uContains(const std::list< V > &list, const V &value)
void RTABMAP_EXP solvePnPRansac(const std::vector< cv::Point3f > &objectPoints, const std::vector< cv::Point2f > &imagePoints, const cv::Mat &cameraMatrix, const cv::Mat &distCoeffs, cv::Mat &rvec, cv::Mat &tvec, bool useExtrinsicGuess, int iterationsCount, float reprojectionError, int minInliersCount, std::vector< int > &inliers, int flags, int refineIterations=1, float refineSigma=3.0f)
std::map< int, Transform > keyFramePoses_
std::map< int, std::vector< CameraModel > > keyFrameModels_
std::vector< V > uValues(const std::multimap< K, V > &mm)
float fundMatrixReprojError_
std::multimap< int, cv::KeyPoint > words
SensorData & sensorData()
T uNormSquared(const std::vector< T > &v)
ULogger class and convenient macros. 
std::vector< int > matchesIDs
std::map< int, float > computeLikelihood(const Signature *signature, const std::list< int > &ids)
std::vector< cv::Point2f > newCorners
virtual void reset(const Transform &initialPose)
float fundMatrixConfidence_
const Transform & getPose() const
std::map< int, std::map< int, cv::Point3f > > keyFrameWords3D_
std::multimap< int, Link > keyFrameLinks_
std::string UTILITE_EXP uNumber2Str(unsigned int number)
std::map< int, cv::Point3f > localMap_
static Optimizer * create(const ParametersMap ¶meters)
const std::multimap< int, int > & getWords() const
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)