28 #include <opencv2/core/core.hpp> 29 #include <opencv2/core/types_c.h> 30 #include <opencv2/highgui/highgui.hpp> 31 #include <opencv2/imgproc/imgproc.hpp> 39 #include <opencv2/calib3d/calib3d.hpp> 48 #include <QApplication> 49 #include <QGraphicsLineItem> 50 #include <QGraphicsPixmapItem> 51 #include <QVBoxLayout> 52 #include <QHBoxLayout> 53 #include <QtCore/QTime> 54 #include <QGraphicsEffect> 62 "rtabmap-epipolar_geometry image1.jpg image2.jpg\n");
70 const cv::Mat & image2,
71 const std::multimap<int, cv::KeyPoint> & words1,
72 const std::multimap<int, cv::KeyPoint> & words2,
73 const std::vector<uchar> & status)
76 this->setLayout(
new QHBoxLayout());
77 this->layout()->setSpacing(0);
78 this->layout()->setContentsMargins(0,0,0,0);
79 this->layout()->addWidget(view1_);
80 view1_->setSceneRect(QRectF(0,0,(
float)image1.cols, (
float)image1.rows));
81 view1_->setLinesShown(
true);
82 view1_->setFeaturesShown(
false);
83 view1_->setImageDepthShown(
true);
86 view1_->setImageDepth(image2);
88 drawKeypoints(words1, words2, status);
96 void drawKeypoints(
const std::multimap<int, cv::KeyPoint> & refWords,
const std::multimap<int, cv::KeyPoint> & loopWords,
const std::vector<uchar> & status)
101 QList<QPair<cv::Point2f, cv::Point2f> > uniqueCorrespondences;
104 for(std::multimap<int, cv::KeyPoint>::const_iterator i = refWords.begin(); i != refWords.end(); ++i )
113 if(
uValues(refWords,
id).size() == 1 &&
uValues(loopWords,
id).size() == 1)
115 uniqueCorrespondences.push_back(QPair<cv::Point2f, cv::Point2f>(i->second.pt,
uValues(loopWords,
id).begin()->pt));
116 inliers.push_back(status[j++]);
119 else if(refWords.count(
id) > 1)
129 view1_->addFeature(
id, i->second, 0, color);
134 UASSERT(uniqueCorrespondences.size() == inliers.size());
135 QList<bool>::iterator jter = inliers.begin();
136 for(QList<QPair<cv::Point2f, cv::Point2f> >::iterator iter = uniqueCorrespondences.begin();
137 iter!=uniqueCorrespondences.end();
145 *jter?Qt::cyan:Qt::red);
155 std::multimap<int, cv::KeyPoint>
aggregate(
const std::list<int> & wordIds,
const std::vector<cv::KeyPoint> & keypoints)
157 std::multimap<int, cv::KeyPoint> words;
158 std::vector<cv::KeyPoint>::const_iterator kpIter = keypoints.begin();
159 for(std::list<int>::const_iterator iter=wordIds.begin(); iter!=wordIds.end(); ++iter)
161 words.insert(std::pair<int, cv::KeyPoint >(*iter, *kpIter));
169 int main(
int argc,
char** argv)
178 image1 = cv::imread(argv[1]);
179 image2 = cv::imread(argv[2]);
193 param.insert(
ParametersPair(Parameters::kSURFExtended(),
"true"));
194 param.insert(
ParametersPair(Parameters::kSURFHessianThreshold(),
"100"));
195 SURF detector(param);
200 UINFO(
"detect/extract features = %d ms", timer.elapsed());
203 std::list<int> wordIds1 = dictionary.
addNewWords(descriptors1, 1);
205 std::list<int> wordIds2 = dictionary.
addNewWords(descriptors2, 2);
206 UINFO(
"quantization to words = %d ms", timer.elapsed());
208 std::multimap<int, cv::KeyPoint> words1 =
aggregate(wordIds1, kpts1);
209 std::multimap<int, cv::KeyPoint> words2 =
aggregate(wordIds2, kpts2);
213 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > pairs;
215 UINFO(
"find pairs = %d ms", timer.elapsed());
219 std::vector<uchar> status;
221 UINFO(
"inliers = %d/%d",
uSum(status), pairs.size());
222 UINFO(
"find F = %d ms", timer.elapsed());
223 if(!fundamentalMatrix.empty())
227 for(std::list<std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> > >::iterator iter=pairs.begin(); iter!=pairs.end(); ++iter)
234 printf(
"x=[%f %f %d]; xp=[%f %f %d];\n",
235 iter->second.first.pt.x,
236 iter->second.first.pt.y,
238 iter->second.second.pt.x,
239 iter->second.second.pt.y,
244 printf(
"x=[x;[%f %f %d]]; xp=[xp;[%f %f %d]];\n",
245 iter->second.first.pt.x,
246 iter->second.first.pt.y,
248 iter->second.second.pt.x,
249 iter->second.second.pt.y,
258 std::cout <<
"F=" << fundamentalMatrix << std::endl;
261 cv::Mat k = cv::Mat::zeros(3,3,CV_64FC1);
262 k.at<
double>(0,0) = image1.cols;
263 k.at<
double>(1,1) = image1.rows;
264 k.at<
double>(2,2) = 1;
265 k.at<
double>(0,2) = image1.cols/2;
266 k.at<
double>(1,2) = image1.rows/2;
270 cv::Mat
e = k.t()*fundamentalMatrix*k;
273 cv::Mat x1(2, goodCount, CV_64FC1);
274 cv::Mat x2(2, goodCount, CV_64FC1);
277 cv::Mat invK = k.inv();
278 for(std::list<std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> > >::iterator iter=pairs.begin(); iter!=pairs.end(); ++iter)
282 cv::Mat tmp(3,1,CV_64FC1);
283 tmp.at<
double>(0,0) = iter->second.first.pt.x;
284 tmp.at<
double>(1,0) = iter->second.first.pt.y;
285 tmp.at<
double>(2,0) = 1;
287 x1.at<
double>(0,j) = tmp.at<
double>(0,0);
288 x1.at<
double>(1,j) = tmp.at<
double>(1,0);
289 tmp.at<
double>(0,0) = iter->second.second.pt.x;
290 tmp.at<
double>(1,0) = iter->second.second.pt.y;
291 tmp.at<
double>(2,0) = 1;
293 x2.at<
double>(0,j) = tmp.at<
double>(0,0);
294 x2.at<
double>(1,j) = tmp.at<
double>(1,0);
295 UDEBUG(
"i=%d j=%d, x1=[%f,%f] x2=[%f,%f]", i, j, x1.at<
double>(0,j), x1.at<
double>(1,j), x2.at<
double>(0,j), x2.at<
double>(1,j));
301 std::cout<<
"K=" << k << std::endl;
305 cv::Mat p0 = cv::Mat::zeros(3, 4, CV_64FC1);
306 p0.at<
double>(0,0) = 1;
307 p0.at<
double>(1,1) = 1;
308 p0.at<
double>(2,2) = 1;
309 UINFO(
"find P from F = %d ms", timer.elapsed());
311 std::cout<<
"P=" << p << std::endl;
316 cv::triangulatePoints(p0, p, x1, x2, x4d);
317 UINFO(
"find X (triangulate) = %d ms", timer.elapsed());
320 for(
int i=0; i<x4d.cols; ++i)
322 x4d.at<
double>(0,i) = x4d.at<
double>(0,i)/x4d.at<
double>(3,i);
323 x4d.at<
double>(1,i) = x4d.at<
double>(1,i)/x4d.at<
double>(3,i);
324 x4d.at<
double>(2,i) = x4d.at<
double>(2,i)/x4d.at<
double>(3,i);
325 x4d.at<
double>(3,i) = x4d.at<
double>(3,i)/x4d.at<
double>(3,i);
328 printf(
"X=[%f;%f;%f;%f];\n",
332 x4d.at<
double>(3,i));
336 printf(
"X=[X [%f;%f;%f;%f]];\n",
340 x4d.at<
double>(3,i));
348 std::cout<<
"R=" << r << std::endl;
349 std::cout<<
"t=" << t << std::endl;
352 QApplication
app(argc, argv);
353 MainWidget mainWidget(image1, image2, words1, words2, status);
359 UINFO(
"Fundamental matrix not found...");
cv::Mat generateDescriptors(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
std::pair< std::string, std::string > ParametersPair
std::multimap< int, cv::KeyPoint > aggregate(const std::list< int > &wordIds, const std::vector< cv::KeyPoint > &keypoints)
std::vector< cv::KeyPoint > generateKeypoints(const cv::Mat &image, const cv::Mat &mask=cv::Mat()) const
void drawKeypoints(const std::multimap< int, cv::KeyPoint > &refWords, const std::multimap< int, cv::KeyPoint > &loopWords, const std::vector< uchar > &status)
MainWidget(const cv::Mat &image1, const cv::Mat &image2, const std::multimap< int, cv::KeyPoint > &words1, const std::multimap< int, cv::KeyPoint > &words2, const std::vector< uchar > &status)
GLM_FUNC_DECL genType e()
virtual std::list< int > addNewWords(const cv::Mat &descriptors, int signatureId)
std::map< std::string, std::string > ParametersMap
Basic mathematics functions.
Some conversion functions.
static void setLevel(ULogger::Level level)
static int findPairsUnique(const std::multimap< int, cv::KeyPoint > &wordsA, const std::multimap< int, cv::KeyPoint > &wordsB, std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > &pairs, bool ignoreNegativeIds=true)
static cv::Mat findFFromWords(const std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > &pairs, std::vector< uchar > &status, double ransacParam1=3.0, double ransacParam2=0.99)
#define UASSERT(condition)
Wrappers of STL for convenient functions.
int main(int argc, char **argv)
#define ULOGGER_DEBUG(...)
QImage uCvMat2QImage(const cv::Mat &image, bool isBgr=true, uCvQtDepthColorMap colorMap=uCvQtDepthWhiteToBlack)
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
virtual void showEvent(QShowEvent *event)
bool uContains(const std::list< V > &list, const V &value)
std::vector< V > uValues(const std::multimap< K, V > &mm)
ULogger class and convenient macros.
static void findRTFromP(const cv::Mat &p, cv::Mat &r, cv::Mat &t)
T uSum(const std::list< T > &list)
static cv::Mat findPFromE(const cv::Mat &E, const cv::Mat &x, const cv::Mat &xp)