47 #include <QApplication> 49 #include <QHBoxLayout> 52 #include <opencv2/core/core.hpp> 59 " rtabmap-matcher [Options] from.png to.png\n" 61 " rtabmap-matcher --Vis/CorNNType 5 --Vis/PnPReprojError 3 from.png to.png\n" 62 " rtabmap-matcher --Vis/CorNNDR 0.8 from.png to.png\n" 63 " rtabmap-matcher --Vis/FeatureType 11 --SuperPoint/ModelPath \"superpoint.pt\" --Vis/CorNNType 6 --PyMatcher/Path \"~/SuperGluePretrainedNetwork/rtabmap_superglue.py\" from.png to.png\n" 64 " rtabmap-matcher --Vis/FeatureType 1 --Vis/CorNNType 6 --PyMatcher/Path \"~/OANet/demo/rtabmap_oanet.py\" --PyMatcher/Model \"~/OANet/model/gl3d/sift-4000/model_best.pth\" from.png to.png\n" 65 " rtabmap-matcher --calibration calib.yaml --from_depth from_depth.png --to_depth to_depth.png from.png to.png\n" 66 " rtabmap-matcher --calibration calibFrom.yaml --calibration_to calibTo.yaml --from_depth from_depth.png --to_depth to_depth.png from.png to.png\n" 67 " rtabmap-matcher --calibration calib.yaml --Vis/FeatureType 2 --Vis/MaxFeatures 10000 --Vis/CorNNType 7 from.png to.png\n" 69 "Note: Use \"Vis/\" parameters for feature stuff.\n" 71 " --calibration \"calibration.yaml\" Calibration file. If not set, a\n" 72 " fake one is created from image's\n" 73 " size (which may not be optimal).\n" 74 " Required if from_depth option is set.\n" 75 " Assuming same calibration for both images\n" 76 " if --calibration_to is not set.\n" 77 " --calibration_to \"calibration.yaml\" Calibration file for \"to\" image. If not set,\n" 78 " the same calibration of --calibration option is\n" 79 " used for \"to\" image.\n" 80 " --from_depth \"from_depth.png\" Depth or right image file of the first image.\n" 81 " If not set, 2D->2D estimation is done by \n" 82 " default. For 3D->2D estimation, from_depth\n" 84 " --to_depth \"to_depth.png\" Depth or right image file of the second image.\n" 85 " For 3D->3D estimation, from_depth and to_depth\n" 86 " should be both set.\n" 103 std::string fromDepthPath;
104 std::string toDepthPath;
105 std::string calibrationPath;
106 std::string calibrationToPath;
107 for(
int i=1; i<argc-2; ++i)
109 if(strcmp(argv[i],
"--from_depth") == 0)
114 fromDepthPath = argv[i];
121 else if(strcmp(argv[i],
"--to_depth") == 0)
126 toDepthPath = argv[i];
133 else if(strcmp(argv[i],
"--calibration") == 0)
138 calibrationPath = argv[i];
145 else if(strcmp(argv[i],
"--calibration_to") == 0)
150 calibrationToPath = argv[i];
157 else if(strcmp(argv[i],
"--help") == 0)
164 printf(
" --calibration = \"%s\"\n", calibrationPath.c_str());
165 if(!calibrationToPath.empty())
167 printf(
" --calibration_to = \"%s\"\n", calibrationToPath.c_str());
169 printf(
" --from_depth = \"%s\"\n", fromDepthPath.c_str());
170 printf(
" --to_depth = \"%s\"\n", toDepthPath.c_str());
173 parameters.insert(
ParametersPair(Parameters::kRegRepeatOnce(),
"false"));
175 cv::Mat imageFrom = cv::imread(argv[argc-2], cv::IMREAD_COLOR);
176 cv::Mat imageTo = cv::imread(argv[argc-1], cv::IMREAD_COLOR);
178 if(!imageFrom.empty() && !imageTo.empty())
186 if(!calibrationPath.empty())
188 if(!fromDepthPath.empty())
190 fromDepth = cv::imread(fromDepthPath, cv::IMREAD_UNCHANGED);
191 if(fromDepth.type() == CV_8UC3)
193 cv::cvtColor(fromDepth, fromDepth, cv::COLOR_BGR2GRAY);
195 else if(fromDepth.empty())
197 printf(
"Failed loading from_depth image: \"%s\"!", fromDepthPath.c_str());
200 if(!toDepthPath.empty())
202 toDepth = cv::imread(toDepthPath, cv::IMREAD_UNCHANGED);
203 if(toDepth.type() == CV_8UC3)
205 cv::cvtColor(toDepth, toDepth, cv::COLOR_BGR2GRAY);
207 else if(toDepth.empty())
209 printf(
"Failed loading to_depth image: \"%s\"!", toDepthPath.c_str());
212 UASSERT(toDepth.empty() || (!fromDepth.empty() && fromDepth.type() == toDepth.type()));
214 else if(!fromDepthPath.empty() || !fromDepthPath.empty())
216 printf(
"A calibration file should be provided if depth images are used!\n");
224 if(!fromDepth.empty())
226 if(fromDepth.type() != CV_8UC1)
230 printf(
"Failed to load calibration file \"%s\"!\n", calibrationPath.c_str());
233 if(calibrationToPath.empty())
242 printf(
"Failed to load calibration file \"%s\"!\n", calibrationPath.c_str());
245 if(calibrationToPath.empty())
247 stereoModelTo = stereoModel;
250 if(!calibrationToPath.empty())
252 if(toDepth.empty() || toDepth.type() != CV_8UC1)
256 printf(
"Failed to load calibration file \"%s\"!\n", calibrationToPath.c_str());
264 printf(
"Failed to load calibration file \"%s\"!\n", calibrationToPath.c_str());
270 else if(!calibrationPath.empty())
274 printf(
"Failed to load calibration file \"%s\"!\n", calibrationPath.c_str());
277 if(!calibrationToPath.empty())
281 printf(
"Failed to load calibration file \"%s\"!\n", calibrationToPath.c_str());
292 printf(
"Using fake calibration model \"from\" (image size=%dx%d): fx=%d fy=%d cx=%d cy=%d\n",
293 imageFrom.cols, imageFrom.rows, imageFrom.cols/2, imageFrom.cols/2, imageFrom.cols/2, imageFrom.rows/2);
294 model =
CameraModel(imageFrom.cols/2, imageFrom.cols/2, imageFrom.cols/2, imageFrom.rows/2);
296 printf(
"Using fake calibration model \"to\" (image size=%dx%d): fx=%d fy=%d cx=%d cy=%d\n",
297 imageTo.cols, imageTo.rows, imageTo.cols/2, imageTo.cols/2, imageTo.cols/2, imageTo.rows/2);
298 modelTo =
CameraModel(imageTo.cols/2, imageTo.cols/2, imageTo.cols/2, imageTo.rows/2);
306 printf(
"Mono calibration model detected.\n");
307 dataFrom =
SensorData(imageFrom, fromDepth, model, 1);
308 dataTo =
SensorData(imageTo, toDepth, modelTo, 2);
312 printf(
"Stereo calibration model detected.\n");
313 dataFrom =
SensorData(imageFrom, fromDepth, stereoModel, 1);
314 dataTo =
SensorData(imageTo, toDepth, stereoModelTo, 2);
321 if(fromDepth.empty())
323 parameters.insert(
ParametersPair(Parameters::kVisEstimationType(),
"2"));
324 parameters.insert(
ParametersPair(Parameters::kVisEpipolarGeometryVar(),
"1"));
325 printf(
"Calibration not set, setting %s=1 and %s=2 by default (2D->2D estimation)\n", Parameters::kVisEpipolarGeometryVar().c_str(), Parameters::kVisEstimationType().c_str());
336 double matchingTime = timer.
ticks();
337 printf(
"Time matching and motion estimation (excluding feature detection): %fs\n", matchingTime);
347 UWARN(
"PyMatcher is selected for matching but binary features " 348 "are not compatible. BruteForce with CrossCheck (%s=5) " 349 "has been used instead.", Parameters::kVisCorNNType().c_str());
352 QApplication
app(argc, argv);
354 float reprojError = Parameters::defaultVisPnPReprojError();
355 std::string pyMatcherPath;
358 dialog.setWindowTitle(QString(
"Matches (%1/%2) %3 sec [%4=%5 (%6) %7=%8 (%9)%10 %11=%12 (%13) %14=%15]")
362 .arg(Parameters::kVisFeatureType().c_str())
365 .arg(Parameters::kVisCorNNType().c_str())
371 .arg(reg.
getNNType()<5?QString(
" %1=%2").arg(Parameters::kVisCorNNDR().c_str()).arg(reg.
getNNDR()):
"")
372 .arg(Parameters::kVisEstimationType().c_str())
375 .arg(Parameters::kVisPnPReprojError().c_str())
394 std::map<int, cv::KeyPoint> kptsFrom;
395 std::map<int, cv::KeyPoint> kptsTo;
396 for(std::map<int, int>::iterator iter=wordsFrom.begin(); iter!=wordsFrom.end(); ++iter)
398 kptsFrom.insert(std::make_pair(iter->first, dataFrom.
getWordsKpts()[iter->second]));
400 for(std::map<int, int>::iterator iter=wordsTo.begin(); iter!=wordsTo.end(); ++iter)
402 kptsTo.insert(std::make_pair(iter->first, dataTo.
getWordsKpts()[iter->second]));
409 pcl::PointCloud<pcl::PointXYZ>::Ptr cloudWordsFrom(
new pcl::PointCloud<pcl::PointXYZ>);
410 cloudWordsFrom->resize(points3d.size());
412 for(std::multimap<int, cv::Point3f>::const_iterator iter=points3d.begin();
413 iter!=points3d.end();
416 cloudWordsFrom->at(i++) = pcl::PointXYZ(iter->second.x, iter->second.y, iter->second.z);
418 if(cloudWordsFrom->size())
422 if(cloudWordsFrom->size())
432 pcl::PointCloud<pcl::PointXYZ>::Ptr cloudWordsFrom(
new pcl::PointCloud<pcl::PointXYZ>);
433 cloudWordsFrom->resize(dataFrom.
getWords3().size());
435 for(std::multimap<int, int>::const_iterator iter=dataFrom.
getWords().begin();
439 const cv::Point3f & pt = dataFrom.
getWords3()[iter->second];
440 cloudWordsFrom->at(i++) = pcl::PointXYZ(pt.x, pt.y, pt.z);
442 if(cloudWordsFrom->size())
446 if(cloudWordsFrom->size())
454 pcl::PointCloud<pcl::PointXYZ>::Ptr cloudWordsTo(
new pcl::PointCloud<pcl::PointXYZ>);
455 cloudWordsTo->resize(dataTo.
getWords3().size());
457 for(std::multimap<int, int>::const_iterator iter=dataTo.
getWords().begin();
461 const cv::Point3f & pt = dataTo.
getWords3()[iter->second];
462 cloudWordsTo->at(i++) = pcl::PointXYZ(pt.x, pt.y, pt.z);
464 if(cloudWordsTo->size())
468 if(cloudWordsTo->size())
470 viewer->
addCloud(
"wordsTo", cloudWordsTo, t, Qt::cyan);
477 QBoxLayout * mainLayout =
new QHBoxLayout();
478 mainLayout->setContentsMargins(0, 0, 0, 0);
479 mainLayout->setSpacing(0);
482 if(imageFrom.cols > imageFrom.rows)
484 dialog.setMinimumWidth(640*(viewer?2:1));
485 dialog.setMinimumHeight(640*imageFrom.rows/imageFrom.cols*2);
486 layout =
new QVBoxLayout();
490 dialog.setMinimumWidth((640*imageFrom.cols/imageFrom.rows*2)*(viewer?2:1));
491 dialog.setMinimumHeight(640);
492 layout =
new QHBoxLayout();
499 layout->setSpacing(0);
500 layout->addWidget(viewA, 1);
501 layout->addWidget(viewB, 1);
503 mainLayout->addLayout(layout, 1);
506 mainLayout->addWidget(viewer, 1);
509 dialog.setLayout(mainLayout);
515 if(!fromDepth.empty())
527 std::multimap<int, cv::KeyPoint> keypointsFrom;
528 std::multimap<int, cv::KeyPoint> keypointsTo;
531 for(std::map<int, int>::const_iterator iter=dataFrom.
getWords().begin(); iter!=dataFrom.
getWords().end(); ++iter)
533 keypointsFrom.insert(keypointsFrom.end(), std::make_pair(iter->first, dataFrom.
getWordsKpts()[iter->second]));
538 for(std::map<int, int>::const_iterator iter=dataTo.
getWords().begin(); iter!=dataTo.
getWords().end(); ++iter)
540 keypointsTo.insert(keypointsTo.end(), std::make_pair(iter->first, dataTo.
getWordsKpts()[iter->second]));
547 const QMultiMap<int, KeypointItem*> & wordsA = viewA->
getFeatures();
548 const QMultiMap<int, KeypointItem*> & wordsB = viewB->
getFeatures();
549 if(wordsA.size() && wordsB.size())
551 QList<int> ids = wordsA.uniqueKeys();
552 for(
int i=0; i<ids.size(); ++i)
554 if(ids[i] > 0 && wordsA.count(ids[i]) == 1 && wordsB.count(ids[i]) == 1)
567 deltaAY = viewA->height()/scaleAX;
571 deltaAX = viewA->width()/scaleAX;
579 deltaBY = viewB->height()/scaleBX;
583 deltaBX = viewA->width()/scaleBX;
591 if(inliersSet.find(ids[i])!=inliersSet.end())
605 kptA->rect().x()+kptA->rect().width()/2,
606 kptA->rect().y()+kptA->rect().height()/2,
607 kptB->rect().x()/scaleDiff+kptB->rect().width()/scaleDiff/2+deltaAX,
608 kptB->rect().y()/scaleDiff+kptB->rect().height()/scaleDiff/2+deltaAY,
612 kptA->rect().x()*scaleDiff+kptA->rect().width()*scaleDiff/2-deltaBX,
613 kptA->rect().y()*scaleDiff+kptA->rect().height()*scaleDiff/2-deltaBY,
614 kptB->rect().x()+kptB->rect().width()/2,
615 kptB->rect().y()+kptB->rect().height()/2,
623 printf(
"Transform: %s\n", t.
prettyPrint().c_str());
624 printf(
"Features: from=%d to=%d\n", (
int)dataFrom.
getWords().size(), (int)dataTo.
getWords().size());
625 printf(
"Matches: %d\n", info.
matches);
626 printf(
"Inliers: %d (%s=%d)\n", info.
inliers, Parameters::kVisMinInliers().c_str(), reg.
getMinInliers());
632 printf(
"Failed loading images %s and %s\n!", argv[argc-2], argv[argc-1]);
void addLine(float x1, float y1, float x2, float y2, QColor color, const QString &text=QString())
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
Transform computeTransformationMod(Signature &from, Signature &to, Transform guess=Transform::getIdentity(), RegistrationInfo *info=0) const
std::map< K, V > uMultimapToMapUnique(const std::multimap< K, V > &m)
void setImageSize(const cv::Size &size)
virtual Feature2D::Type getType() const =0
void setGridShown(bool shown)
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)
void addOrUpdateCoordinate(const std::string &id, const Transform &transform, double scale, bool foreground=false)
static const char * showUsage()
void setFeatureColor(int id, QColor color)
static std::string getDir(const std::string &filePath)
std::pair< std::string, std::string > ParametersPair
const cv::Mat & getWordsDescriptors() const
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP removeNaNFromPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
QImage uCvMat2QImage(const cv::Mat &image, bool isBgr=true, uCvQtDepthColorMap colorMap=uCvQtDepthWhiteToBlack, float depthMin=0, float depthMax=0)
static ParametersMap parseArguments(int argc, char *argv[], bool onlyParameters=false)
std::map< std::string, std::string > ParametersMap
const std::vector< cv::Point3f > & getWords3() const
int main(int argc, char *argv[])
std::vector< int > inliersIDs
bool load(const std::string &filePath)
void setImage(const QImage &image)
static void setLevel(ULogger::Level level)
int getMinInliers() const
const std::vector< cv::KeyPoint > & getWordsKpts() const
#define UASSERT(condition)
Wrappers of STL for convenient functions.
std::list< std::string > uSplit(const std::string &str, char separator=' ')
void setImageDepth(const cv::Mat &imageDepth)
static std::string nnStrategyName(NNStrategy strategy)
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
void setCloudPointSize(const std::string &id, int size)
static std::string typeName(Type type)
bool addCloud(const std::string &id, const pcl::PCLPointCloud2Ptr &binaryCloud, const Transform &pose, bool rgb, bool hasNormals, bool hasIntensity, const QColor &color=QColor(), int viewport=1)
bool load(const std::string &directory, const std::string &cameraName, bool ignoreStereoTransform=true)
const Feature2D * getDetector() const
const QColor & getDefaultMatchingFeatureColor() const
SensorData & sensorData()
ULogger class and convenient macros.
int getEstimationType() const
std::string UTILITE_EXP uFormat(const char *fmt,...)
bool isValidForProjection() const
void setFeatures(const std::multimap< int, cv::KeyPoint > &refWords, const cv::Mat &depth=cv::Mat(), const QColor &color=Qt::yellow)
const QColor & getDefaultMatchingLineColor() const
const QMultiMap< int, rtabmap::KeypointItem * > & getFeatures() const
const std::multimap< int, int > & getWords() const
void setImageDepthShown(bool shown)
const CameraModel & left() const