Skip to content
Snippets Groups Projects
Commit 9a47e8d0 authored by Joan Solà Ortega's avatar Joan Solà Ortega
Browse files
parents 71c6afa9 744689a9
No related branches found
No related tags found
No related merge requests found
#edit the following line to add the librarie's header files
FIND_PATH(OpenCV_CONFIG OpenCVConfig.cmake /usr/local/share/OpenCV)
IF (OpenCV_CONFIG)
INCLUDE (/usr/local/share/OpenCV/OpenCVConfig.cmake)
ENDIF (OpenCV_CONFIG)
\ No newline at end of file
...@@ -200,6 +200,7 @@ SET(headers_alg_anms ...@@ -200,6 +200,7 @@ SET(headers_alg_anms
# locate the necessary dependencies # locate the necessary dependencies
FIND_PACKAGE(Eigen3 REQUIRED) FIND_PACKAGE(Eigen3 REQUIRED)
FIND_PACKAGE(OpenCV REQUIRED) FIND_PACKAGE(OpenCV REQUIRED)
#INCLUDE (${PROJECT_SOURCE_DIR}/cmake_modules/FindOpenCV.cmake)
#FIND_PACKAGE(Boost REQUIRED) #FIND_PACKAGE(Boost REQUIRED)
if (OpenCV_FOUND) if (OpenCV_FOUND)
......
...@@ -33,7 +33,7 @@ int main(int argc, char** argv) ...@@ -33,7 +33,7 @@ int main(int argc, char** argv)
cv::VideoCapture capture; cv::VideoCapture capture;
if (argc < 2) if (argc < 2)
{ {
std::cout << "Please use\n\t./test_opencv <arg> " std::cout << "Please use\n\t./fundamental_matrix <arg> "
"\nwith " "\nwith "
"\n\targ = <path/videoname.mp4> for video input " "\n\targ = <path/videoname.mp4> for video input "
"\n\targ = 0 for camera input." << std::endl; "\n\targ = 0 for camera input." << std::endl;
...@@ -58,23 +58,81 @@ int main(int argc, char** argv) ...@@ -58,23 +58,81 @@ int main(int argc, char** argv)
else else
std::cout << "succeded" << std::endl; std::cout << "succeded" << std::endl;
// set image detector // YAML file with parameters
vision_utils::DetectorParamsORBPtr det_params = std::make_shared<vision_utils::DetectorParamsORB>(); std::string path_yaml_file = "/src/examples/yaml";
vision_utils::DetectorBasePtr det_b_ptr = vision_utils::setupDetector("ORB", "ORB detector", det_params); std::string vu_root = _VU_ROOT_DIR; // Root dir path
vision_utils::DetectorORBPtr det_ptr = std::static_pointer_cast<vision_utils::DetectorORB>(det_b_ptr); std::string yaml_file_params_vision_utils = vu_root + path_yaml_file + "/fundamental_matrix.yaml";
// set image descriptor // Detector
vision_utils::DescriptorParamsORBPtr desc_params = std::make_shared<vision_utils::DescriptorParamsORB>(); std::string det_name = vision_utils::readYamlType(yaml_file_params_vision_utils, "detector");
vision_utils::DescriptorBasePtr des_b_ptr = vision_utils::setupDescriptor("ORB", "ORB detector", desc_params); vision_utils::DetectorBasePtr det_ptr = vision_utils::setupDetector(det_name, det_name + " detector", yaml_file_params_vision_utils);
vision_utils::DescriptorORBPtr des_ptr = std::static_pointer_cast<vision_utils::DescriptorORB>(des_b_ptr);
if (det_name.compare("ORB") == 0)
// set matcher det_ptr = std::static_pointer_cast<vision_utils::DetectorORB>(det_ptr);
std::string matcher_name = "BRUTEFORCE_HAMMING_2"; else if (det_name.compare("FAST") == 0)
vision_utils::MatcherParamsBasePtr mat_params = std::make_shared<vision_utils::MatcherParamsBase>(matcher_name); det_ptr = std::static_pointer_cast<vision_utils::DetectorFAST>(det_ptr);
mat_params->match_type = vision_utils::MATCH; else if (det_name.compare("SIFT") == 0)
vision_utils::MatcherBasePtr mat_b_ptr = vision_utils::setupMatcher(matcher_name, matcher_name, mat_params); det_ptr = std::static_pointer_cast<vision_utils::DetectorSIFT>(det_ptr);
vision_utils::MatcherBRUTEFORCE_HAMMING_2Ptr mat_ptr = std::static_pointer_cast<vision_utils::MatcherBRUTEFORCE_HAMMING_2>(mat_b_ptr); else if (det_name.compare("SURF") == 0)
det_ptr = std::static_pointer_cast<vision_utils::DetectorSURF>(det_ptr);
else if (det_name.compare("BRISK") == 0)
det_ptr = std::static_pointer_cast<vision_utils::DetectorBRISK>(det_ptr);
else if (det_name.compare("MSER") == 0)
det_ptr = std::static_pointer_cast<vision_utils::DetectorMSER>(det_ptr);
else if (det_name.compare("GFTT") == 0)
det_ptr = std::static_pointer_cast<vision_utils::DetectorGFTT>(det_ptr);
else if (det_name.compare("HARRIS") == 0)
det_ptr = std::static_pointer_cast<vision_utils::DetectorHARRIS>(det_ptr);
else if (det_name.compare("SBD") == 0)
det_ptr = std::static_pointer_cast<vision_utils::DetectorSBD>(det_ptr);
else if (det_name.compare("KAZE") == 0)
det_ptr = std::static_pointer_cast<vision_utils::DetectorKAZE>(det_ptr);
else if (det_name.compare("AKAZE") == 0)
det_ptr = std::static_pointer_cast<vision_utils::DetectorAKAZE>(det_ptr);
else if (det_name.compare("AGAST") == 0)
det_ptr = std::static_pointer_cast<vision_utils::DetectorAGAST>(det_ptr);
// Descriptor
std::string des_name = vision_utils::readYamlType(yaml_file_params_vision_utils, "descriptor");
vision_utils::DescriptorBasePtr des_ptr = vision_utils::setupDescriptor(des_name, des_name + " descriptor", yaml_file_params_vision_utils);
if (des_name.compare("ORB") == 0)
des_ptr = std::static_pointer_cast<vision_utils::DescriptorORB>(des_ptr);
else if (des_name.compare("SIFT") == 0)
des_ptr = std::static_pointer_cast<vision_utils::DescriptorSIFT>(des_ptr);
else if (des_name.compare("SURF") == 0)
des_ptr = std::static_pointer_cast<vision_utils::DescriptorSURF>(des_ptr);
else if (des_name.compare("BRISK") == 0)
des_ptr = std::static_pointer_cast<vision_utils::DescriptorBRISK>(des_ptr);
else if (des_name.compare("KAZE") == 0)
des_ptr = std::static_pointer_cast<vision_utils::DescriptorKAZE>(des_ptr);
else if (des_name.compare("AKAZE") == 0)
des_ptr = std::static_pointer_cast<vision_utils::DescriptorAKAZE>(des_ptr);
else if (des_name.compare("LATCH") == 0)
des_ptr = std::static_pointer_cast<vision_utils::DescriptorLATCH>(des_ptr);
else if (des_name.compare("FREAK") == 0)
des_ptr = std::static_pointer_cast<vision_utils::DescriptorFREAK>(des_ptr);
else if (des_name.compare("BRIEF") == 0)
des_ptr = std::static_pointer_cast<vision_utils::DescriptorBRIEF>(des_ptr);
else if (des_name.compare("DAISY") == 0)
des_ptr = std::static_pointer_cast<vision_utils::DescriptorDAISY>(des_ptr);
else if (des_name.compare("LUCID") == 0)
des_ptr = std::static_pointer_cast<vision_utils::DescriptorLUCID>(des_ptr);
// Matcher
std::string mat_name = vision_utils::readYamlType(yaml_file_params_vision_utils, "matcher");
vision_utils::MatcherBasePtr mat_ptr = vision_utils::setupMatcher(mat_name, mat_name + " matcher", yaml_file_params_vision_utils);
if (mat_name.compare("FLANNBASED") == 0)
mat_ptr = std::static_pointer_cast<vision_utils::MatcherFLANNBASED>(mat_ptr);
if (mat_name.compare("BRUTEFORCE") == 0)
mat_ptr = std::static_pointer_cast<vision_utils::MatcherBRUTEFORCE>(mat_ptr);
if (mat_name.compare("BRUTEFORCE_L1") == 0)
mat_ptr = std::static_pointer_cast<vision_utils::MatcherBRUTEFORCE_L1>(mat_ptr);
if (mat_name.compare("BRUTEFORCE_HAMMING") == 0)
mat_ptr = std::static_pointer_cast<vision_utils::MatcherBRUTEFORCE_HAMMING>(mat_ptr);
if (mat_name.compare("BRUTEFORCE_HAMMING_2") == 0)
mat_ptr = std::static_pointer_cast<vision_utils::MatcherBRUTEFORCE_HAMMING_2>(mat_ptr);
// set and print image properties // set and print image properties
unsigned int img_width = (unsigned int)capture.get(CV_CAP_PROP_FRAME_WIDTH); unsigned int img_width = (unsigned int)capture.get(CV_CAP_PROP_FRAME_WIDTH);
...@@ -91,7 +149,6 @@ int main(int argc, char** argv) ...@@ -91,7 +149,6 @@ int main(int argc, char** argv)
cv::namedWindow("Feature tracker"); // Creates a window for display. cv::namedWindow("Feature tracker"); // Creates a window for display.
cv::moveWindow("Feature tracker", 0, 0); cv::moveWindow("Feature tracker", 0, 0);
// First image // First image
KeyPointVector keypoints_1 = det_ptr->detect(image_buffer.back()); KeyPointVector keypoints_1 = det_ptr->detect(image_buffer.back());
cv::Mat descriptors_1 = des_ptr->getDescriptor( image_buffer.back(), keypoints_1); cv::Mat descriptors_1 = des_ptr->getDescriptor( image_buffer.back(), keypoints_1);
...@@ -117,7 +174,7 @@ int main(int argc, char** argv) ...@@ -117,7 +174,7 @@ int main(int argc, char** argv)
{ {
image_buffer.add(img); image_buffer.add(img);
cv::Mat descriptors_2 = des_ptr->getDescriptor( image_buffer.back(), keypoints_1); cv::Mat descriptors_2 = des_ptr->getDescriptor( image_buffer.back(), keypoints_2);
unsigned int max_dist = 0; unsigned int max_dist = 0;
unsigned int min_dist = 512; unsigned int min_dist = 512;
...@@ -175,9 +232,9 @@ int main(int argc, char** argv) ...@@ -175,9 +232,9 @@ int main(int argc, char** argv)
std::cout << "Matches: initial " << matches.size() << " | good " << good_matches.size() << " | inliers " std::cout << "Matches: initial " << matches.size() << " | good " << good_matches.size() << " | inliers "
<< inlier_matches.size() << std::endl; << inlier_matches.size() << std::endl;
std::cout << "+++++++++++++++" << std::endl; std::cout << "kp1: " << keypoints_1.size() << " kp2: " << keypoints_2.size() << " inliers:" << inlier_matches.size() << std::endl;
std::cout << keypoints_1.size() << " " << keypoints_2.size() << " " << inlier_matches.size() << " " << img_matches.size() << std::endl;
std::cout << "+++++++++++++++" << std::endl;
// Draw RANSAC inliers // Draw RANSAC inliers
cv::drawMatches(image_buffer[image_buffer.size()-2], // before the last img cv::drawMatches(image_buffer[image_buffer.size()-2], // before the last img
......
detector:
type: "AGAST"
threshold: 10
nonmaxSuppression: true
detection type: 3 # AGAST_5_8=0, AGAST_7_12d=1, AGAST_7_12s=2, OAST_9_16=3, THRESHOLD=10000, NONMAX_SUPPRESSION=10001
descriptor:
type: "BRIEF"
bytes: 32
use_orientation: false
matcher:
type: "FLANNBASED" # BRUTEFORCE, BRUTEFORCE_HAMMING, BRUTEFORCE_HAMMING_2, BRUTEFORCE_L1, FLANNBASED
match type: 1 # Match type. MATCH = 1, KNNMATCH = 2, RADIUSMATCH = 3
min normalized score: 0.8
\ No newline at end of file
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment