├── .clang-format ├── .gitignore ├── src ├── aif_assert.hpp ├── generate_target_file.cpp ├── generate_parameter_file.cpp ├── match_features.cpp └── extract_features.cpp ├── README.md ├── include └── affine_invariant_features │ ├── results.hpp │ ├── parallel_tasks.hpp │ ├── cv_serializable.hpp │ ├── affine_invariant_feature_base.hpp │ ├── target.hpp │ ├── result_matcher.hpp │ ├── feature_parameters.hpp │ └── affine_invariant_feature.hpp ├── LICENSE ├── package.xml └── CMakeLists.txt /.clang-format: -------------------------------------------------------------------------------- 1 | BasedOnStyle: LLVM 2 | ColumnLimit: 100 3 | SpacesInAngles: true -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # Compiled Object files 2 | *.slo 3 | *.lo 4 | *.o 5 | *.obj 6 | 7 | # Precompiled Headers 8 | *.gch 9 | *.pch 10 | 11 | # Compiled Dynamic libraries 12 | *.so 13 | *.dylib 14 | *.dll 15 | 16 | # Fortran module files 17 | *.mod 18 | *.smod 19 | 20 | # Compiled Static libraries 21 | *.lai 22 | *.la 23 | *.a 24 | *.lib 25 | 26 | # Executables 27 | *.exe 28 | *.out 29 | *.app 30 | 31 | # VSCode settings 32 | .vscode/ 33 | -------------------------------------------------------------------------------- /src/aif_assert.hpp: -------------------------------------------------------------------------------- 1 | #ifndef AIF_ASSERT 2 | #define AIF_ASSERT 3 | 4 | #include 5 | 6 | // print the given message and raise an error if the given expression is ture 7 | #define AIF_Assert(expr, ...) \ 8 | if (!!(expr)) \ 9 | ; \ 10 | else \ 11 | CV_Error_(cv::Error::StsAssert, (__VA_ARGS__)) 12 | 13 | #endif -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # affine_invariant_features 2 | A c++ header-only implementation of an affine invariant feature sampling technique used in ASIFT 3 | 4 | ## Features 5 | * implemented in c++ 6 | * supports all keypoint detection or descriptor extraction algorithms in OpenCV 7 | * supports parallel processing 8 | 9 | ## Dependencies (and tested versions) 10 | * Boost (1.58) 11 | * OpenCV (3.1.0) 12 | * OpenSSL (1.0.2) 13 | * ROS (kinetic, only using filesystem and catkin build system) 14 | 15 | ## References 16 | * http://www.cmap.polytechnique.fr/~yu/research/ASIFT/demo.html 17 | * https://github.com/opencv/opencv/blob/master/samples/python/asift.py 18 | * http://www.mattsheckells.com/opencv-asift-c-implementation/ 19 | -------------------------------------------------------------------------------- /include/affine_invariant_features/results.hpp: -------------------------------------------------------------------------------- 1 | #ifndef AFFINE_INVARIANT_FEATURES_RESULTS 2 | #define AFFINE_INVARIANT_FEATURES_RESULTS 3 | 4 | #include 5 | #include 6 | 7 | #include 8 | 9 | #include 10 | #include 11 | 12 | namespace affine_invariant_features { 13 | 14 | struct Results : public CvSerializable { 15 | public: 16 | Results() {} 17 | 18 | virtual ~Results() {} 19 | 20 | virtual void read(const cv::FileNode &fn) { 21 | fn["keypoints"] >> keypoints; 22 | fn["descriptors"] >> descriptors; 23 | fn["normType"] >> normType; 24 | } 25 | 26 | virtual void write(cv::FileStorage &fs) const { 27 | fs << "keypoints" << keypoints; 28 | fs << "descriptors" << descriptors; 29 | fs << "normType" << normType; 30 | } 31 | 32 | virtual std::string getDefaultName() const { return "Results"; } 33 | 34 | public: 35 | std::vector< cv::KeyPoint > keypoints; 36 | cv::Mat descriptors; 37 | int normType; // cv::NormTypes 38 | }; 39 | 40 | } // namespace affine_invariant_features 41 | 42 | #endif -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2016 yoshito-n-students 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /include/affine_invariant_features/parallel_tasks.hpp: -------------------------------------------------------------------------------- 1 | #ifndef AFFINE_INVARIANT_FEATURES_PARALLEL_TASKS 2 | #define AFFINE_INVARIANT_FEATURES_PARALLEL_TASKS 3 | 4 | #include 5 | #include 6 | #include 7 | 8 | #include 9 | 10 | #include 11 | 12 | namespace affine_invariant_features { 13 | 14 | class ParallelTasks : public std::vector< boost::function< void() > >, public cv::ParallelLoopBody { 15 | private: 16 | typedef std::vector< boost::function< void() > > Base; 17 | 18 | public: 19 | ParallelTasks() : Base() {} 20 | 21 | ParallelTasks(const size_type count) : Base(count) {} 22 | 23 | ParallelTasks(const size_type count, const value_type &value) : Base(count, value) {} 24 | 25 | virtual ~ParallelTasks() {} 26 | 27 | virtual void operator()(const cv::Range &range) const { 28 | for (int i = range.start; i < range.end; ++i) { 29 | // handle an exception from the task 30 | // because it cannot be catched by the main thread running cv::parallel_for_() 31 | try { 32 | // at() may throw std::out_of_range unlike the operator [] 33 | const value_type &task(at(i)); 34 | CV_Assert(task); 35 | task(); 36 | } catch (const std::exception &error) { 37 | std::cerr << "Parallel task [" << i << "]: " << error.what() << std::endl; 38 | } catch (...) { 39 | std::cerr << "Parallel task [" << i << "]: Non-standard error" << std::endl; 40 | } 41 | } 42 | } 43 | }; 44 | 45 | } // namespace affine_invariant_features 46 | 47 | #endif -------------------------------------------------------------------------------- /include/affine_invariant_features/cv_serializable.hpp: -------------------------------------------------------------------------------- 1 | #ifndef AFFINE_INVARIANT_FEATURES_CV_SERIALIZABLE 2 | #define AFFINE_INVARIANT_FEATURES_CV_SERIALIZABLE 3 | 4 | #include 5 | 6 | #include 7 | #include 8 | 9 | #include 10 | 11 | namespace affine_invariant_features { 12 | 13 | struct CvSerializable { 14 | public: 15 | CvSerializable() {} 16 | 17 | virtual ~CvSerializable() {} 18 | 19 | // return the name of type 20 | virtual std::string getDefaultName() const = 0; 21 | 22 | // read name-value pairs corresponding member variables 23 | virtual void read(const cv::FileNode &) = 0; 24 | 25 | // write name-value pairs corresponding member variables 26 | virtual void write(cv::FileStorage &) const = 0; 27 | 28 | // write the name of type and members 29 | virtual void save(cv::FileStorage &fs) const { 30 | fs << getDefaultName() << "{"; 31 | write(fs); 32 | fs << "}"; 33 | } 34 | }; 35 | 36 | // read members belonging the name of type, if there 37 | template < typename T > 38 | typename boost::enable_if< boost::is_base_of< CvSerializable, T >, cv::Ptr< T > >::type 39 | load(const cv::FileNode &fn) { 40 | const cv::Ptr< T > val(new T()); 41 | const cv::FileNode node(fn[val->getDefaultName()]); 42 | if (node.empty()) { 43 | return cv::Ptr< T >(); 44 | } else { 45 | val->read(node); 46 | return val; 47 | } 48 | } 49 | 50 | // called by operator>>(cv::FileNode, T) 51 | template < typename T > 52 | typename boost::enable_if< boost::is_base_of< CvSerializable, T > >::type 53 | read(const cv::FileNode &fn, T &val, const T &default_val) { 54 | if (fn.empty()) { 55 | val = default_val; 56 | } else { 57 | val.read(fn); 58 | } 59 | } 60 | 61 | // called by operator<<(cv::FileStorage, T) 62 | static inline void write(cv::FileStorage &fs, const std::string &, const CvSerializable &val) { 63 | val.write(fs); 64 | } 65 | 66 | } // namespace affine_invariant_features 67 | 68 | #endif -------------------------------------------------------------------------------- /src/generate_target_file.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | #include 5 | 6 | #include 7 | #include 8 | 9 | #include "aif_assert.hpp" 10 | 11 | int main(int argc, char *argv[]) { 12 | namespace aif = affine_invariant_features; 13 | 14 | const cv::CommandLineParser args( 15 | argc, argv, "{ help | | }" 16 | "{ @image | | absolute, or relative to the current path or }" 17 | "{ @file | | output file describing the image }" 18 | "{ @package | | optional name of a ROS package where the image locates }"); 19 | 20 | if (args.has("help")) { 21 | args.printMessage(); 22 | return 0; 23 | } 24 | 25 | const std::string image_path(args.get< std::string >("@image")); 26 | const std::string file_path(args.get< std::string >("@file")); 27 | const std::string package_name(args.get< std::string >("@package")); 28 | if (!args.check()) { 29 | args.printErrors(); 30 | return 1; 31 | } 32 | 33 | const std::string resolved_path(aif::TargetDescription::resolvePath(package_name, image_path)); 34 | const cv::Mat image(cv::imread(resolved_path)); 35 | AIF_Assert(!image.empty(), "No image file at %s", resolved_path.c_str()); 36 | 37 | aif::TargetDescription target; 38 | target.package = package_name; 39 | target.path = image_path; 40 | target.md5 = aif::TargetDescription::generateMD5(resolved_path); 41 | target.contour.push_back(cv::Point(0, 0)); 42 | target.contour.push_back(cv::Point(image.cols - 1, 0)); 43 | target.contour.push_back(cv::Point(image.cols - 1, image.rows - 1)); 44 | target.contour.push_back(cv::Point(0, image.rows - 1)); 45 | 46 | cv::FileStorage file(file_path, cv::FileStorage::WRITE); 47 | AIF_Assert(file.isOpened(), "Could not open or create %s", file_path.c_str()); 48 | 49 | target.save(file); 50 | std::cout << "Wrote a description of " << resolved_path << " to " << file_path << std::endl; 51 | 52 | return 0; 53 | } 54 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | affine_invariant_features 4 | 0.0.0 5 | The affine_invariant_features package 6 | 7 | 8 | 9 | 10 | yoshito 11 | 12 | 13 | 14 | 15 | 16 | TODO 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | catkin 43 | roscpp 44 | roslib 45 | roscpp 46 | roslib 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | -------------------------------------------------------------------------------- /src/generate_parameter_file.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | 5 | #include 6 | 7 | #include 8 | 9 | #include "aif_assert.hpp" 10 | 11 | int main(int argc, char *argv[]) { 12 | 13 | namespace aif = affine_invariant_features; 14 | 15 | const cv::CommandLineParser args( 16 | argc, argv, 17 | "{ help | | }" 18 | "{ non-aif | | generate non affine invariant feature parameters }" 19 | "{ list | | list available type names of parameter sets }" 20 | "{ @type | | type of first parameter set }" 21 | "{ @file | | output file }" 22 | "{ @type2 | | type of second parameter set (optional) }"); 23 | 24 | if (args.has("help")) { 25 | args.printMessage(); 26 | return 0; 27 | } 28 | 29 | if (args.has("list")) { 30 | const std::vector< std::string > names(aif::getFeatureParameterNames()); 31 | for (std::vector< std::string >::const_iterator name = names.begin(); name != names.end(); 32 | ++name) { 33 | std::cout << *name << std::endl; 34 | } 35 | return 0; 36 | } 37 | 38 | const std::string type(args.get< std::string >("@type")); 39 | const std::string type2(args.get< std::string >("@type2")); 40 | const std::string path(args.get< std::string >("@file")); 41 | const bool non_aif(args.has("non-aif")); 42 | if (!args.check()) { 43 | args.printErrors(); 44 | return 1; 45 | } 46 | 47 | aif::AIFParameters params; 48 | 49 | params.push_back(aif::createFeatureParameters(type)); 50 | AIF_Assert(params.back(), "Could not create the first parameter set whose type is %s", 51 | type.c_str()); 52 | 53 | if (!type2.empty()) { 54 | params.push_back(aif::createFeatureParameters(type2)); 55 | AIF_Assert(params.back(), "Could not create the second parameter set whose type is %s", 56 | type2.c_str()); 57 | } 58 | 59 | cv::FileStorage file(path, cv::FileStorage::WRITE); 60 | AIF_Assert(file.isOpened(), "Could not open or create %s", path.c_str()); 61 | 62 | if (non_aif) { 63 | params[0]->save(file); 64 | std::cout << "Wrote a parameter set whose type is " << type << " to " << path << std::endl; 65 | } else { 66 | params.save(file); 67 | std::cout << "Wrote a parameter set whose type is " << params.getDefaultName() << " to " << path 68 | << std::endl; 69 | } 70 | 71 | return 0; 72 | } 73 | -------------------------------------------------------------------------------- /include/affine_invariant_features/affine_invariant_feature_base.hpp: -------------------------------------------------------------------------------- 1 | #ifndef AFFINE_INVARIANT_FEATURES_AFFINE_INVARIANT_FEATURE_BASE 2 | #define AFFINE_INVARIANT_FEATURES_AFFINE_INVARIANT_FEATURE_BASE 3 | 4 | #include 5 | #include 6 | 7 | namespace affine_invariant_features { 8 | 9 | // 10 | // A base class of AffineInvariantFeature to hold a backend feature algorithm 11 | // 12 | 13 | class AffineInvariantFeatureBase : public cv::Feature2D { 14 | protected: 15 | AffineInvariantFeatureBase(const cv::Ptr< cv::Feature2D > detector, 16 | const cv::Ptr< cv::Feature2D > extractor) 17 | : detector_(detector), extractor_(extractor) {} 18 | 19 | public: 20 | virtual ~AffineInvariantFeatureBase() {} 21 | 22 | // 23 | // inherited functions from cv::Feature2D or its base class. 24 | // These just call corresponding one of the base feature. 25 | // detect(), compute(), detectAndCompute() and getDefaultName() 26 | // are overloaded in AffineInvariantFeature. 27 | // 28 | 29 | virtual int defaultNorm() const { 30 | CV_Assert(extractor_); 31 | return extractor_->defaultNorm(); 32 | } 33 | 34 | virtual int descriptorSize() const { 35 | CV_Assert(extractor_); 36 | return extractor_->descriptorSize(); 37 | } 38 | 39 | virtual int descriptorType() const { 40 | CV_Assert(extractor_); 41 | return extractor_->descriptorType(); 42 | } 43 | 44 | virtual bool empty() const { 45 | if (detector_) { 46 | if (!detector_->empty()) { 47 | return false; 48 | } 49 | } 50 | if (extractor_) { 51 | if (!extractor_->empty()) { 52 | return false; 53 | } 54 | } 55 | return true; 56 | } 57 | 58 | virtual void read(const cv::FileNode &fn) { 59 | if (detector_) { 60 | detector_->read(fn); 61 | } 62 | if (extractor_ && extractor_ != detector_) { 63 | extractor_->read(fn); 64 | } 65 | } 66 | 67 | virtual void write(cv::FileStorage &fs) const { 68 | if (detector_) { 69 | detector_->write(fs); 70 | } 71 | if (extractor_ && extractor_ != detector_) { 72 | extractor_->write(fs); 73 | } 74 | } 75 | 76 | virtual void clear() { 77 | if (detector_) { 78 | detector_->clear(); 79 | } 80 | if (extractor_ && extractor_ != detector_) { 81 | extractor_->clear(); 82 | } 83 | } 84 | 85 | virtual void save(const cv::String &filename) const { 86 | if (detector_) { 87 | detector_->save(filename); 88 | } 89 | if (extractor_ && extractor_ != detector_) { 90 | extractor_->save(filename); 91 | } 92 | } 93 | 94 | protected: 95 | const cv::Ptr< cv::Feature2D > detector_; 96 | const cv::Ptr< cv::Feature2D > extractor_; 97 | }; 98 | 99 | } // namespace affine_invariant_features 100 | 101 | #endif -------------------------------------------------------------------------------- /src/match_features.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | #include 10 | #include 11 | 12 | #include "aif_assert.hpp" 13 | 14 | namespace aif = affine_invariant_features; 15 | 16 | void loadAll(const std::string &path, cv::Ptr< aif::TargetData > &target_data, 17 | cv::Ptr< aif::Results > &results) { 18 | const cv::FileStorage file(path, cv::FileStorage::READ); 19 | AIF_Assert(file.isOpened(), "Could not open %s", path.c_str()); 20 | 21 | target_data = aif::load< aif::TargetData >(file.root()); 22 | AIF_Assert(target_data, "Could not load target data described in %s", path.c_str()); 23 | 24 | results = aif::load< aif::Results >(file.root()); 25 | AIF_Assert(results, "Could not load features from %s", path.c_str()); 26 | } 27 | 28 | cv::Mat shade(const cv::Mat &src, const cv::Mat &mask) { 29 | cv::Mat dst(src / 4); 30 | src.copyTo(dst, mask); 31 | return dst; 32 | } 33 | 34 | int main(int argc, char *argv[]) { 35 | 36 | const cv::CommandLineParser args( 37 | argc, argv, "{ help | | }" 38 | "{ @feature-file1 | | can be generated by extract_features }" 39 | "{ @feature-file2 | | can be generated by extract_features }" 40 | "{ @image | | optional output image }"); 41 | 42 | if (args.has("help")) { 43 | args.printMessage(); 44 | return 0; 45 | } 46 | 47 | const std::string feature_path1(args.get< std::string >("@feature-file1")); 48 | const std::string feature_path2(args.get< std::string >("@feature-file2")); 49 | const std::string image_path(args.get< std::string >("@image")); 50 | if (!args.check()) { 51 | args.printErrors(); 52 | return 1; 53 | } 54 | 55 | cv::Ptr< aif::TargetData > target1; 56 | cv::Ptr< aif::Results > results1; 57 | loadAll(feature_path1, target1, results1); 58 | std::cout << "loaded " << results1->keypoints.size() << " feature points from " << feature_path1 59 | << std::endl; 60 | 61 | cv::Ptr< aif::TargetData > target2; 62 | cv::Ptr< aif::Results > results2; 63 | loadAll(feature_path2, target2, results2); 64 | std::cout << "loaded " << results2->keypoints.size() << " feature points from " << feature_path2 65 | << std::endl; 66 | 67 | aif::ResultMatcher matcher(results2); 68 | std::cout << "Matching feature points. This may take seconds." << std::endl; 69 | cv::Matx33f transform; 70 | std::vector< cv::DMatch > matches; 71 | matcher.match(*results1, transform, matches); 72 | std::cout << "found " << matches.size() << " matches" << std::endl; 73 | 74 | const cv::Mat image1(shade(target1->image, target1->mask)); 75 | const cv::Mat image2(shade(target2->image, target2->mask)); 76 | cv::Mat image; 77 | cv::drawMatches(image1, results1->keypoints, image2, results2->keypoints, matches, image); 78 | 79 | std::cout << "Showing feature points and matches. Press any key to continue." << std::endl; 80 | cv::imshow("Matches", image); 81 | cv::waitKey(0); 82 | 83 | if (!image_path.empty()) { 84 | cv::imwrite(image_path, image); 85 | std::cout << "Wrote the result image to " << image_path << std::endl; 86 | } 87 | 88 | return 0; 89 | } 90 | -------------------------------------------------------------------------------- /src/extract_features.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | #include 10 | #include 11 | #include 12 | 13 | #include "aif_assert.hpp" 14 | 15 | int main(int argc, char *argv[]) { 16 | namespace aif = affine_invariant_features; 17 | 18 | const cv::CommandLineParser args( 19 | argc, argv, "{ help | | }" 20 | "{ @parameter-file | | can be generated by generate_parameter_file }" 21 | "{ @target-file | | can be generated by generate_target_file }" 22 | "{ @result-file | | }"); 23 | 24 | if (args.has("help")) { 25 | args.printMessage(); 26 | return 0; 27 | } 28 | 29 | const std::string param_path(args.get< std::string >("@parameter-file")); 30 | const std::string target_path(args.get< std::string >("@target-file")); 31 | const std::string result_path(args.get< std::string >("@result-file")); 32 | if (!args.check()) { 33 | args.printErrors(); 34 | return 1; 35 | } 36 | 37 | const cv::FileStorage param_file(param_path, cv::FileStorage::READ); 38 | AIF_Assert(param_file.isOpened(), "Could not open %s", param_path.c_str()); 39 | 40 | const cv::Ptr< const aif::FeatureParameters > params( 41 | aif::load< aif::FeatureParameters >(param_file.root())); 42 | AIF_Assert(params, "Could not load a parameter set from %s", param_path.c_str()); 43 | 44 | const cv::Ptr< cv::Feature2D > feature(params->createFeature()); 45 | AIF_Assert(feature, "Could not create a feature algorithm from %s", param_path.c_str()); 46 | 47 | const cv::FileStorage target_file(target_path, cv::FileStorage::READ); 48 | AIF_Assert(target_file.isOpened(), "Could not open %s", target_path.c_str()); 49 | 50 | const cv::Ptr< const aif::TargetDescription > target_desc( 51 | aif::load< aif::TargetDescription >(target_file.root())); 52 | AIF_Assert(target_desc, "Could not load an target description from %s", target_path.c_str()); 53 | 54 | const cv::Ptr< const aif::TargetData > target_data(aif::TargetData::retrieve(*target_desc)); 55 | AIF_Assert(target_data, "Could not load target data described in %s", target_path.c_str()); 56 | 57 | cv::Mat target_image(target_data->image / 4); 58 | target_data->image.copyTo(target_image, target_data->mask); 59 | std::cout << "Showing the target image with mask. Press any key to continue." << std::endl; 60 | cv::imshow("Target", target_image); 61 | cv::waitKey(0); 62 | 63 | std::cout << "Extracting features. This may take seconds or minutes." << std::endl; 64 | aif::Results results; 65 | feature->detectAndCompute(target_data->image, target_data->mask, results.keypoints, 66 | results.descriptors); 67 | results.normType = feature->defaultNorm(); 68 | 69 | cv::Mat result_image; 70 | cv::drawKeypoints(target_image, results.keypoints, result_image); 71 | std::cout << "Showing a result image with keypoints. Press any key to continue." << std::endl; 72 | cv::imshow("Results", result_image); 73 | cv::waitKey(0); 74 | 75 | cv::FileStorage result_file(result_path, cv::FileStorage::WRITE); 76 | AIF_Assert(result_file.isOpened(), "Could not open or create %s", result_path.c_str()); 77 | 78 | params->save(result_file); 79 | target_desc->save(result_file); 80 | results.save(result_file); 81 | std::cout << "Wrote context and results of feature extraction to " << result_path << std::endl; 82 | 83 | return 0; 84 | } 85 | -------------------------------------------------------------------------------- /include/affine_invariant_features/target.hpp: -------------------------------------------------------------------------------- 1 | #ifndef AFFINE_INVARIANT_FEATURES_TARGET 2 | #define AFFINE_INVARIANT_FEATURES_TARGET 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | #include 11 | 12 | #include 13 | 14 | #include 15 | 16 | #include 17 | #include 18 | #include 19 | 20 | #include 21 | 22 | namespace affine_invariant_features { 23 | 24 | struct TargetDescription : public CvSerializable { 25 | public: 26 | TargetDescription() {} 27 | 28 | virtual ~TargetDescription() {} 29 | 30 | virtual void read(const cv::FileNode &fn) { 31 | fn["package"] >> package; 32 | fn["path"] >> path; 33 | fn["md5"] >> md5; 34 | const cv::FileNode contour_node(fn["contour"]); 35 | const std::size_t contour_size(contour_node.isSeq() ? contour_node.size() : 0); 36 | contour.resize(contour_size); 37 | for (std::size_t i = 0; i < contour_size; ++i) { 38 | contour_node[i] >> contour[i]; 39 | } 40 | } 41 | 42 | virtual void write(cv::FileStorage &fs) const { 43 | fs << "package" << package; 44 | fs << "path" << path; 45 | fs << "md5" << md5; 46 | fs << "contour"; 47 | fs << "[:"; 48 | for (std::vector< cv::Point >::const_iterator point = contour.begin(); point != contour.end(); 49 | ++point) { 50 | fs << *point; 51 | } 52 | fs << "]"; 53 | } 54 | 55 | virtual std::string getDefaultName() const { return "TargetDescription"; } 56 | 57 | public: 58 | static std::string resolvePath(const std::string &package, const std::string &path) { 59 | namespace bf = boost::filesystem; 60 | namespace rp = ros::package; 61 | 62 | const bf::path root_path(package.empty() ? std::string() : rp::getPath(package)); 63 | const bf::path leaf_path(path); 64 | if (root_path.empty() || leaf_path.empty() || leaf_path.is_absolute()) { 65 | return leaf_path.string(); 66 | } 67 | return (root_path / leaf_path).string(); 68 | } 69 | 70 | static std::string generateMD5(const std::string &path) { 71 | // open the file path as a binary file 72 | std::ifstream ifs(path.c_str(), std::ios::binary); 73 | if (!ifs) { 74 | return std::string(); 75 | } 76 | 77 | // calculate the MD5 hash using openSSL library 78 | unsigned char md5[MD5_DIGEST_LENGTH]; 79 | { 80 | MD5_CTX ctx; 81 | MD5_Init(&ctx); 82 | char buf[4096]; 83 | while (ifs.read(buf, 4096) || ifs.gcount()) { 84 | MD5_Update(&ctx, buf, ifs.gcount()); 85 | } 86 | MD5_Final(md5, &ctx); 87 | } 88 | 89 | // stringaze the MD5 hash 90 | std::ostringstream oss; 91 | for (int i = 0; i < MD5_DIGEST_LENGTH; ++i) { 92 | oss << std::hex << std::setw(2) << std::setfill('0') << static_cast< int >(md5[i]); 93 | } 94 | 95 | return oss.str(); 96 | } 97 | 98 | public: 99 | std::string package; 100 | std::string path; 101 | std::string md5; 102 | std::vector< cv::Point > contour; 103 | }; 104 | 105 | struct TargetData : public CvSerializable { 106 | public: 107 | TargetData() {} 108 | 109 | virtual ~TargetData() {} 110 | 111 | virtual void read(const cv::FileNode &fn) { 112 | TargetDescription desc; 113 | desc.read(fn); 114 | 115 | const cv::Ptr< const TargetData > data(retrieve(desc)); 116 | *this = data ? *data : TargetData(); 117 | } 118 | 119 | virtual void write(cv::FileStorage &fs) const { CV_Error(cv::Error::StsNotImplemented, ""); } 120 | 121 | virtual std::string getDefaultName() const { return "TargetData"; } 122 | 123 | public: 124 | static cv::Ptr< TargetData > retrieve(const TargetDescription &desc, 125 | const bool check_md5 = false) { 126 | const std::string path(TargetDescription::resolvePath(desc.package, desc.path)); 127 | if (path.empty()) { 128 | return cv::Ptr< TargetData >(); 129 | } 130 | 131 | if (check_md5) { 132 | if (desc.md5.empty() || desc.md5 != TargetDescription::generateMD5(path)) { 133 | return cv::Ptr< TargetData >(); 134 | } 135 | } 136 | 137 | const cv::Ptr< TargetData > data(new TargetData()); 138 | data->image = cv::imread(path); 139 | if (data->image.empty()) { 140 | return cv::Ptr< TargetData >(); 141 | } 142 | 143 | if (!desc.contour.empty()) { 144 | data->mask = cv::Mat::zeros(data->image.size(), CV_8UC1); 145 | cv::fillPoly(data->mask, std::vector< std::vector< cv::Point > >(1, desc.contour), 255); 146 | } 147 | return data; 148 | } 149 | 150 | public: 151 | cv::Mat image; 152 | cv::Mat mask; 153 | }; 154 | 155 | template <> cv::Ptr< TargetData > load< TargetData >(const cv::FileNode &fn) { 156 | const cv::Ptr< const TargetDescription > desc(load< TargetDescription >(fn)); 157 | return desc ? TargetData::retrieve(*desc) : cv::Ptr< TargetData >(); 158 | } 159 | 160 | } // namespace affine_invariant_features 161 | 162 | #endif -------------------------------------------------------------------------------- /include/affine_invariant_features/result_matcher.hpp: -------------------------------------------------------------------------------- 1 | #ifndef AFFINE_INVARIANT_FEATURES_RESULT_MATCHER 2 | #define AFFINE_INVARIANT_FEATURES_RESULT_MATCHER 3 | 4 | #include 5 | #include 6 | 7 | #include 8 | #include 9 | #include 10 | 11 | #include 12 | #include 13 | 14 | #include 15 | #include 16 | #include 17 | #include 18 | 19 | namespace affine_invariant_features { 20 | 21 | class ResultMatcher { 22 | public: 23 | ResultMatcher(const cv::Ptr< const Results > &reference) : reference_(reference) { 24 | CV_Assert(reference_); 25 | 26 | switch (reference_->normType) { 27 | case cv::NORM_L2: 28 | matcher_ = new cv::FlannBasedMatcher(new cv::flann::KDTreeIndexParams(4)); 29 | break; 30 | case cv::NORM_HAMMING: 31 | matcher_ = new cv::FlannBasedMatcher(new cv::flann::LshIndexParams(6, 12, 1)); 32 | break; 33 | } 34 | 35 | CV_Assert(matcher_); 36 | 37 | matcher_->add(reference_->descriptors); 38 | matcher_->train(); 39 | } 40 | 41 | virtual ~ResultMatcher() {} 42 | 43 | const Results &getReference() const { return *reference_; } 44 | 45 | void match(const Results &source, cv::Matx33f &transform, std::vector< cv::DMatch > &matches, 46 | const double min_match_ratio = 0.) const { 47 | // number of matches wanted 48 | const int n_min_matches(std::ceil(min_match_ratio * reference_->keypoints.size())); 49 | 50 | // find the 1st & 2nd matches for each descriptor in the source 51 | std::vector< std::vector< cv::DMatch > > all_matches; 52 | matcher_->knnMatch(source.descriptors, all_matches, 2); 53 | 54 | // filter unique matches whose 1st is enough better than 2nd 55 | std::vector< cv::DMatch > unique_matches; 56 | for (std::vector< std::vector< cv::DMatch > >::const_iterator m = all_matches.begin(); 57 | m != all_matches.end(); ++m) { 58 | if (m->size() < 2) { 59 | continue; 60 | } 61 | if ((*m)[0].distance > 0.75 * (*m)[1].distance) { 62 | continue; 63 | } 64 | unique_matches.push_back((*m)[0]); 65 | } 66 | if (unique_matches.size() < std::max(n_min_matches, 4)) { 67 | // abort if the number of unique matches is less than required. 68 | // 4 is the minimum requirement for cv::findHomography(). 69 | matches.clear(); 70 | return; 71 | } 72 | 73 | // further filter matches compatible to a registration 74 | std::vector< unsigned char > mask; 75 | { 76 | std::vector< cv::Point2f > source_points; 77 | std::vector< cv::Point2f > reference_points; 78 | for (std::vector< cv::DMatch >::const_iterator m = unique_matches.begin(); 79 | m != unique_matches.end(); ++m) { 80 | source_points.push_back(source.keypoints[m->queryIdx].pt); 81 | reference_points.push_back(reference_->keypoints[m->trainIdx].pt); 82 | } 83 | try { 84 | transform = cv::findHomography(source_points, reference_points, cv::RANSAC, 5., mask); 85 | } catch (const cv::Exception & /* error */) { 86 | // abort if cv::findHomography() is failed. this can happen when no good transform is found. 87 | ROS_INFO("An exception from cv::findHomography() was properly handled. " 88 | "An error message may be printed just before this message but it is still ok."); 89 | matches.clear(); 90 | return; 91 | } 92 | } 93 | 94 | // pack the final matches 95 | matches.clear(); 96 | for (std::size_t i = 0; i < unique_matches.size(); ++i) { 97 | if (mask[i] == 0) { 98 | continue; 99 | } 100 | matches.push_back(unique_matches[i]); 101 | } 102 | if (matches.size() < n_min_matches) { 103 | // abort if the number of matches is not enough 104 | matches.clear(); 105 | return; 106 | } 107 | } 108 | 109 | static void parallelMatch(const std::vector< cv::Ptr< const ResultMatcher > > &matchers, 110 | const Results &source, std::vector< cv::Matx33f > &transforms, 111 | std::vector< std::vector< cv::DMatch > > &matches_array, 112 | const std::vector< double > &min_match_ratios = std::vector< double >(), 113 | const double nstripes = -1.) { 114 | CV_Assert(min_match_ratios.empty() || matchers.size() == min_match_ratios.size()); 115 | 116 | // initiate output 117 | const int ntasks(matchers.size()); 118 | transforms.resize(ntasks, cv::Matx33f::eye()); 119 | matches_array.resize(ntasks); 120 | 121 | // populate tasks 122 | ParallelTasks tasks(ntasks); 123 | for (int i = 0; i < ntasks; ++i) { 124 | if (matchers[i]) { 125 | tasks[i] = boost::bind(&ResultMatcher::match, matchers[i].get(), boost::ref(source), 126 | boost::ref(transforms[i]), boost::ref(matches_array[i]), 127 | min_match_ratios.empty() ? 0. : min_match_ratios[i]); 128 | } 129 | } 130 | 131 | // do paralell matching 132 | cv::parallel_for_(cv::Range(0, ntasks), tasks, nstripes); 133 | } 134 | 135 | private: 136 | const cv::Ptr< const Results > reference_; 137 | cv::Ptr< cv::DescriptorMatcher > matcher_; 138 | }; 139 | 140 | } // namespace affine_invariant_features 141 | 142 | #endif -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(affine_invariant_features) 3 | 4 | ## Find catkin macros and libraries 5 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) 6 | ## is used, also find other catkin packages 7 | find_package( 8 | catkin REQUIRED COMPONENTS 9 | roscpp 10 | roslib 11 | ) 12 | 13 | ## System dependencies are found with CMake's conventions 14 | find_package( 15 | Boost REQUIRED COMPONENTS 16 | filesystem 17 | ) 18 | find_package( 19 | OpenCV REQUIRED COMPONENTS 20 | calib3d 21 | core 22 | features2d 23 | flann 24 | highgui 25 | imgproc 26 | xfeatures2d 27 | ) 28 | find_package( 29 | OpenSSL REQUIRED 30 | ) 31 | 32 | ## Uncomment this if the package has a setup.py. This macro ensures 33 | ## modules and global scripts declared therein get installed 34 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html 35 | # catkin_python_setup() 36 | 37 | ################################################ 38 | ## Declare ROS messages, services and actions ## 39 | ################################################ 40 | 41 | ## To declare and build messages, services or actions from within this 42 | ## package, follow these steps: 43 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in 44 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). 45 | ## * In the file package.xml: 46 | ## * add a build_depend tag for "message_generation" 47 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET 48 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in 49 | ## but can be declared for certainty nonetheless: 50 | ## * add a run_depend tag for "message_runtime" 51 | ## * In this file (CMakeLists.txt): 52 | ## * add "message_generation" and every package in MSG_DEP_SET to 53 | ## find_package(catkin REQUIRED COMPONENTS ...) 54 | ## * add "message_runtime" and every package in MSG_DEP_SET to 55 | ## catkin_package(CATKIN_DEPENDS ...) 56 | ## * uncomment the add_*_files sections below as needed 57 | ## and list every .msg/.srv/.action file to be processed 58 | ## * uncomment the generate_messages entry below 59 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) 60 | 61 | ## Generate messages in the 'msg' folder 62 | # add_message_files( 63 | # FILES 64 | # Message1.msg 65 | # Message2.msg 66 | # ) 67 | 68 | ## Generate services in the 'srv' folder 69 | # add_service_files( 70 | # FILES 71 | # Service1.srv 72 | # Service2.srv 73 | # ) 74 | 75 | ## Generate actions in the 'action' folder 76 | # add_action_files( 77 | # FILES 78 | # Action1.action 79 | # Action2.action 80 | # ) 81 | 82 | ## Generate added messages and services with any dependencies listed here 83 | # generate_messages( 84 | # DEPENDENCIES 85 | # std_msgs # Or other packages containing msgs 86 | # ) 87 | 88 | ################################################ 89 | ## Declare ROS dynamic reconfigure parameters ## 90 | ################################################ 91 | 92 | ## To declare and build dynamic reconfigure parameters within this 93 | ## package, follow these steps: 94 | ## * In the file package.xml: 95 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure" 96 | ## * In this file (CMakeLists.txt): 97 | ## * add "dynamic_reconfigure" to 98 | ## find_package(catkin REQUIRED COMPONENTS ...) 99 | ## * uncomment the "generate_dynamic_reconfigure_options" section below 100 | ## and list every .cfg file to be processed 101 | 102 | ## Generate dynamic reconfigure parameters in the 'cfg' folder 103 | # generate_dynamic_reconfigure_options( 104 | # cfg/DynReconf1.cfg 105 | # cfg/DynReconf2.cfg 106 | # ) 107 | 108 | ################################### 109 | ## catkin specific configuration ## 110 | ################################### 111 | ## The catkin_package macro generates cmake config files for your package 112 | ## Declare things to be passed to dependent projects 113 | ## INCLUDE_DIRS: uncomment this if you package contains header files 114 | ## LIBRARIES: libraries you create in this project that dependent projects also need 115 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need 116 | ## DEPENDS: system dependencies of this project that dependent projects also need 117 | catkin_package( 118 | INCLUDE_DIRS include 119 | LIBRARIES ${Boost_LIBRARIES} ${OpenCV_LIBRARIES} ${OPENSSL_LIBRARIES} #affine_invariant_features 120 | CATKIN_DEPENDS roscpp roslib 121 | # DEPENDS system_lib 122 | ) 123 | 124 | ########### 125 | ## Build ## 126 | ########### 127 | 128 | ## Specify additional locations of header files 129 | ## Your package locations should be listed before other locations 130 | # include_directories(include) 131 | include_directories( 132 | include 133 | ${catkin_INCLUDE_DIRS} 134 | ${Boost_INCLUDE_DIRS} 135 | ${OpenCV_INCLUDE_DIRS} 136 | ${OPENSSL_INCLUDE_DIR} 137 | ) 138 | 139 | ## Declare a C++ library 140 | # add_library(affine_invariant_features 141 | # src/${PROJECT_NAME}/affine_invariant_features.cpp 142 | # ) 143 | 144 | ## Add cmake target dependencies of the library 145 | ## as an example, code may need to be generated before libraries 146 | ## either from message generation or dynamic reconfigure 147 | # add_dependencies(affine_invariant_features ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 148 | 149 | ## Declare a C++ executable 150 | add_executable( 151 | generate_parameter_file 152 | src/generate_parameter_file.cpp 153 | ) 154 | add_executable( 155 | generate_target_file 156 | src/generate_target_file.cpp 157 | ) 158 | add_executable( 159 | extract_features 160 | src/extract_features.cpp 161 | ) 162 | add_executable( 163 | match_features 164 | src/match_features.cpp 165 | ) 166 | 167 | ## Add cmake target dependencies of the executable 168 | ## same as for the library above 169 | # add_dependencies(affine_invariant_features_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 170 | 171 | ## Specify libraries to link a library or executable target against 172 | target_link_libraries( 173 | generate_parameter_file 174 | ${catkin_LIBRARIES} 175 | ${Boost_LIBRARIES} 176 | ${OpenCV_LIBRARIES} 177 | ${OPENSSL_LIBRARIES} 178 | ) 179 | target_link_libraries( 180 | generate_target_file 181 | ${catkin_LIBRARIES} 182 | ${Boost_LIBRARIES} 183 | ${OpenCV_LIBRARIES} 184 | ${OPENSSL_LIBRARIES} 185 | ) 186 | target_link_libraries( 187 | extract_features 188 | ${catkin_LIBRARIES} 189 | ${Boost_LIBRARIES} 190 | ${OpenCV_LIBRARIES} 191 | ${OPENSSL_LIBRARIES} 192 | ) 193 | target_link_libraries( 194 | match_features 195 | ${catkin_LIBRARIES} 196 | ${Boost_LIBRARIES} 197 | ${OpenCV_LIBRARIES} 198 | ${OPENSSL_LIBRARIES} 199 | ) 200 | 201 | ############# 202 | ## Install ## 203 | ############# 204 | 205 | # all install targets should use catkin DESTINATION variables 206 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html 207 | 208 | ## Mark executable scripts (Python etc.) for installation 209 | ## in contrast to setup.py, you can choose the destination 210 | # install(PROGRAMS 211 | # scripts/my_python_script 212 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 213 | # ) 214 | 215 | ## Mark executables and/or libraries for installation 216 | # install(TARGETS affine_invariant_features affine_invariant_features_node 217 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 218 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 219 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 220 | # ) 221 | 222 | ## Mark cpp header files for installation 223 | # install(DIRECTORY include/${PROJECT_NAME}/ 224 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 225 | # FILES_MATCHING PATTERN "*.h" 226 | # PATTERN ".svn" EXCLUDE 227 | # ) 228 | 229 | ## Mark other files for installation (e.g. launch and bag files, etc.) 230 | # install(FILES 231 | # # myfile1 232 | # # myfile2 233 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 234 | # ) 235 | 236 | ############# 237 | ## Testing ## 238 | ############# 239 | 240 | ## Add gtest based cpp test target and link libraries 241 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_affine_invariant_features.cpp) 242 | # if(TARGET ${PROJECT_NAME}-test) 243 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) 244 | # endif() 245 | 246 | ## Add folders to be run by python nosetests 247 | # catkin_add_nosetests(test) 248 | -------------------------------------------------------------------------------- /include/affine_invariant_features/feature_parameters.hpp: -------------------------------------------------------------------------------- 1 | #ifndef AFFINE_INVARIANT_FEATURES_FEATURE_PARAMETERS 2 | #define AFFINE_INVARIANT_FEATURES_FEATURE_PARAMETERS 3 | 4 | #include 5 | #include 6 | 7 | #include 8 | #include 9 | 10 | #include 11 | #include 12 | #include 13 | 14 | namespace affine_invariant_features { 15 | 16 | // 17 | // A base class for parameter sets of feature detectors and descriptor extractors 18 | // 19 | 20 | struct FeatureParameters : public CvSerializable { 21 | public: 22 | FeatureParameters() {} 23 | 24 | virtual ~FeatureParameters() {} 25 | 26 | virtual cv::Ptr< cv::Feature2D > createFeature() const = 0; 27 | }; 28 | 29 | // 30 | // Affine invariant sampled feature 31 | // 32 | 33 | static cv::Ptr< FeatureParameters > createFeatureParameters(const std::string &); 34 | 35 | struct AIFParameters : public std::vector< cv::Ptr< FeatureParameters > >, 36 | public FeatureParameters { 37 | public: 38 | AIFParameters() {} 39 | 40 | virtual ~AIFParameters() {} 41 | 42 | virtual cv::Ptr< cv::Feature2D > createFeature() const { 43 | switch (size()) { 44 | case 0: 45 | return cv::Ptr< cv::Feature2D >(); 46 | case 1: 47 | return AffineInvariantFeature::create((*this)[0] ? (*this)[0]->createFeature() 48 | : cv::Ptr< cv::Feature2D >()); 49 | default: 50 | return AffineInvariantFeature::create( 51 | (*this)[0] ? (*this)[0]->createFeature() : cv::Ptr< cv::Feature2D >(), 52 | (*this)[1] ? (*this)[1]->createFeature() : cv::Ptr< cv::Feature2D >()); 53 | } 54 | } 55 | 56 | virtual void read(const cv::FileNode &fn) { 57 | clear(); 58 | for (cv::FileNodeIterator node = fn.begin(); node != fn.end(); ++node) { 59 | if (!(*node).isNamed()) { // operator-> did not work 60 | continue; 61 | } 62 | const cv::Ptr< FeatureParameters > p(createFeatureParameters((*node).name())); 63 | if (!p) { 64 | continue; 65 | } 66 | p->read(*node); 67 | push_back(p); 68 | } 69 | } 70 | 71 | virtual void write(cv::FileStorage &fs) const { 72 | for (std::vector< cv::Ptr< FeatureParameters > >::const_iterator p = begin(); p != end(); ++p) { 73 | if (!(*p)) { 74 | continue; 75 | } 76 | fs << (*p)->getDefaultName() << "{"; 77 | (*p)->write(fs); 78 | fs << "}"; 79 | } 80 | } 81 | 82 | virtual std::string getDefaultName() const { return "AIFParameters"; } 83 | }; 84 | 85 | // 86 | // AKAZE 87 | // 88 | 89 | struct AKAZEParameters : public FeatureParameters { 90 | public: 91 | AKAZEParameters() 92 | : descriptorType(defaultAKAZE().getDescriptorType()), 93 | descriptorSize(defaultAKAZE().getDescriptorSize()), 94 | descriptorChannels(defaultAKAZE().getDescriptorChannels()), 95 | threshold(defaultAKAZE().getThreshold()), nOctaves(defaultAKAZE().getNOctaves()), 96 | nOctaveLayers(defaultAKAZE().getNOctaveLayers()), 97 | diffusivity(defaultAKAZE().getDiffusivity()) {} 98 | 99 | virtual ~AKAZEParameters() {} 100 | 101 | virtual cv::Ptr< cv::Feature2D > createFeature() const { 102 | return cv::AKAZE::create(descriptorType, descriptorSize, descriptorChannels, threshold, 103 | nOctaves, nOctaveLayers, diffusivity); 104 | } 105 | 106 | virtual void read(const cv::FileNode &fn) { 107 | fn["descriptorType"] >> descriptorType; 108 | fn["descriptorSize"] >> descriptorSize; 109 | fn["descriptorChannels"] >> descriptorChannels; 110 | fn["threshold"] >> threshold; 111 | fn["nOctaves"] >> nOctaves; 112 | fn["nOctaveLayers"] >> nOctaveLayers; 113 | fn["diffusivity"] >> diffusivity; 114 | } 115 | 116 | virtual void write(cv::FileStorage &fs) const { 117 | fs << "descriptorType" << descriptorType; 118 | fs << "descriptorSize" << descriptorSize; 119 | fs << "descriptorChannels" << descriptorChannels; 120 | fs << "threshold" << threshold; 121 | fs << "nOctaves" << nOctaves; 122 | fs << "nOctaveLayers" << nOctaveLayers; 123 | fs << "diffusivity" << diffusivity; 124 | } 125 | 126 | virtual std::string getDefaultName() const { return "AKAZEParameters"; } 127 | 128 | protected: 129 | static const cv::AKAZE &defaultAKAZE() { 130 | static cv::Ptr< const cv::AKAZE > default_akaze(cv::AKAZE::create()); 131 | CV_Assert(default_akaze); 132 | return *default_akaze; 133 | } 134 | 135 | public: 136 | int descriptorType; 137 | int descriptorSize; 138 | int descriptorChannels; 139 | float threshold; 140 | int nOctaves; 141 | int nOctaveLayers; 142 | int diffusivity; 143 | }; 144 | 145 | // 146 | // BRISK 147 | // 148 | 149 | struct BRISKParameters : public FeatureParameters { 150 | public: 151 | // Note: like SIFT, no interface to access default BRISK parameters 152 | BRISKParameters() : threshold(30), nOctaves(3), patternScale(1.0f) {} 153 | 154 | virtual ~BRISKParameters() {} 155 | 156 | virtual cv::Ptr< cv::Feature2D > createFeature() const { 157 | return cv::BRISK::create(threshold, nOctaves, patternScale); 158 | } 159 | 160 | virtual void read(const cv::FileNode &fn) { 161 | fn["threshold"] >> threshold; 162 | fn["nOctaves"] >> nOctaves; 163 | fn["patternScale"] >> patternScale; 164 | } 165 | 166 | virtual void write(cv::FileStorage &fs) const { 167 | fs << "threshold" << threshold; 168 | fs << "nOctaves" << nOctaves; 169 | fs << "patternScale" << patternScale; 170 | } 171 | 172 | virtual std::string getDefaultName() const { return "BRISKParameters"; } 173 | 174 | public: 175 | int threshold; 176 | int nOctaves; 177 | float patternScale; 178 | }; 179 | 180 | // 181 | // SIFT 182 | // 183 | 184 | struct SIFTParameters : public FeatureParameters { 185 | public: 186 | // opencv does not provide interfaces to access default SIFT parameters. 187 | // thus values below are copied from online reference. 188 | SIFTParameters() 189 | : nfeatures(0), nOctaveLayers(3), contrastThreshold(0.04), edgeThreshold(10.), sigma(1.6) {} 190 | 191 | virtual ~SIFTParameters() {} 192 | 193 | virtual cv::Ptr< cv::Feature2D > createFeature() const { 194 | return cv::xfeatures2d::SIFT::create(nfeatures, nOctaveLayers, contrastThreshold, edgeThreshold, 195 | sigma); 196 | } 197 | 198 | virtual void read(const cv::FileNode &fn) { 199 | fn["nfeatures"] >> nfeatures; 200 | fn["nOctaveLayers"] >> nOctaveLayers; 201 | fn["contrastThreshold"] >> contrastThreshold; 202 | fn["edgeThreshold"] >> edgeThreshold; 203 | fn["sigma"] >> sigma; 204 | } 205 | 206 | virtual void write(cv::FileStorage &fs) const { 207 | fs << "nfeatures" << nfeatures; 208 | fs << "nOctaveLayers" << nOctaveLayers; 209 | fs << "contrastThreshold" << contrastThreshold; 210 | fs << "edgeThreshold" << edgeThreshold; 211 | fs << "sigma" << sigma; 212 | } 213 | 214 | virtual std::string getDefaultName() const { return "SIFTParameters"; } 215 | 216 | public: 217 | int nfeatures; 218 | int nOctaveLayers; 219 | double contrastThreshold; 220 | double edgeThreshold; 221 | double sigma; 222 | }; 223 | 224 | // 225 | // SURF 226 | // 227 | 228 | struct SURFParameters : public FeatureParameters { 229 | public: 230 | SURFParameters() 231 | : hessianThreshold(defaultSURF().getHessianThreshold()), 232 | nOctaves(defaultSURF().getNOctaves()), nOctaveLayers(defaultSURF().getNOctaveLayers()), 233 | extended(defaultSURF().getExtended()), upright(defaultSURF().getUpright()) {} 234 | 235 | virtual ~SURFParameters() {} 236 | 237 | virtual cv::Ptr< cv::Feature2D > createFeature() const { 238 | return cv::xfeatures2d::SURF::create(hessianThreshold, nOctaves, nOctaveLayers, extended, 239 | upright); 240 | } 241 | 242 | virtual void read(const cv::FileNode &fn) { 243 | fn["hessianThreshold"] >> hessianThreshold; 244 | fn["nOctaves"] >> nOctaves; 245 | fn["nOctaveLayers"] >> nOctaveLayers; 246 | fn["extended"] >> extended; 247 | fn["upright"] >> upright; 248 | } 249 | 250 | virtual void write(cv::FileStorage &fs) const { 251 | fs << "hessianThreshold" << hessianThreshold; 252 | fs << "nOctaves" << nOctaves; 253 | fs << "nOctaveLayers" << nOctaveLayers; 254 | fs << "extended" << extended; 255 | fs << "upright" << upright; 256 | } 257 | 258 | virtual std::string getDefaultName() const { return "SURFParameters"; } 259 | 260 | protected: 261 | static const cv::xfeatures2d::SURF &defaultSURF() { 262 | static cv::Ptr< const cv::xfeatures2d::SURF > default_surf(cv::xfeatures2d::SURF::create()); 263 | CV_Assert(default_surf); 264 | return *default_surf; 265 | } 266 | 267 | public: 268 | double hessianThreshold; 269 | int nOctaves; 270 | int nOctaveLayers; 271 | bool extended; 272 | bool upright; 273 | }; 274 | 275 | // 276 | // Utility functions to create or read variants of FeatureParameters 277 | // 278 | 279 | #define AIF_APPEND_DEFAULT_NAME(names, type) \ 280 | do { \ 281 | const cv::Ptr< type > params(new type()); \ 282 | names.push_back(params->getDefaultName()); \ 283 | } while (false) 284 | 285 | static inline std::vector< std::string > getFeatureParameterNames() { 286 | std::vector< std::string > names; 287 | AIF_APPEND_DEFAULT_NAME(names, AIFParameters); 288 | AIF_APPEND_DEFAULT_NAME(names, AKAZEParameters); 289 | AIF_APPEND_DEFAULT_NAME(names, BRISKParameters); 290 | AIF_APPEND_DEFAULT_NAME(names, SIFTParameters); 291 | AIF_APPEND_DEFAULT_NAME(names, SURFParameters); 292 | return names; 293 | } 294 | 295 | #define AIF_RETURN_IF_CREATE(type) \ 296 | do { \ 297 | const cv::Ptr< type > params(new type()); \ 298 | if (type_name == params->getDefaultName()) { \ 299 | return params; \ 300 | } \ 301 | } while (false) 302 | 303 | static inline cv::Ptr< FeatureParameters > createFeatureParameters(const std::string &type_name) { 304 | AIF_RETURN_IF_CREATE(AIFParameters); 305 | AIF_RETURN_IF_CREATE(AKAZEParameters); 306 | AIF_RETURN_IF_CREATE(BRISKParameters); 307 | AIF_RETURN_IF_CREATE(SIFTParameters); 308 | AIF_RETURN_IF_CREATE(SURFParameters); 309 | return cv::Ptr< FeatureParameters >(); 310 | } 311 | 312 | #define AIF_RETURN_IF_LOAD(type) \ 313 | do { \ 314 | const cv::Ptr< type > params(load< type >(fn)); \ 315 | if (params) { \ 316 | return params; \ 317 | } \ 318 | } while (false) 319 | 320 | template <> cv::Ptr< FeatureParameters > load< FeatureParameters >(const cv::FileNode &fn) { 321 | AIF_RETURN_IF_LOAD(AIFParameters); 322 | AIF_RETURN_IF_LOAD(AKAZEParameters); 323 | AIF_RETURN_IF_LOAD(BRISKParameters); 324 | AIF_RETURN_IF_LOAD(SIFTParameters); 325 | AIF_RETURN_IF_LOAD(SURFParameters); 326 | return cv::Ptr< FeatureParameters >(); 327 | } 328 | 329 | } // namespace affine_invariant_features 330 | 331 | #endif -------------------------------------------------------------------------------- /include/affine_invariant_features/affine_invariant_feature.hpp: -------------------------------------------------------------------------------- 1 | #ifndef AFFINE_INVARIANT_FEATURES_AFFINE_INVARIANT_FEATURE 2 | #define AFFINE_INVARIANT_FEATURES_AFFINE_INVARIANT_FEATURE 3 | 4 | #include 5 | #include 6 | 7 | #include 8 | #include 9 | 10 | #include 11 | #include 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | namespace affine_invariant_features { 18 | 19 | // 20 | // AffineInvariantFeature that samples features in various affine transformation space 21 | // 22 | 23 | class AffineInvariantFeature : public AffineInvariantFeatureBase { 24 | protected: 25 | // the private constructor. users must use create() to instantiate an AffineInvariantFeature 26 | AffineInvariantFeature(const cv::Ptr< cv::Feature2D > detector, 27 | const cv::Ptr< cv::Feature2D > extractor, const double nstripes) 28 | : AffineInvariantFeatureBase(detector, extractor), nstripes_(nstripes) { 29 | // generate parameters for affine invariant sampling 30 | phi_params_.push_back(0.); 31 | tilt_params_.push_back(1.); 32 | for (int i = 1; i < 6; ++i) { 33 | const double tilt(std::pow(2., 0.5 * i)); 34 | for (double phi = 0.; phi < 180.; phi += 72. / tilt) { 35 | phi_params_.push_back(phi); 36 | tilt_params_.push_back(tilt); 37 | } 38 | } 39 | ntasks_ = phi_params_.size(); 40 | } 41 | 42 | public: 43 | virtual ~AffineInvariantFeature() {} 44 | 45 | // 46 | // unique interfaces to instantiate an AffineInvariantFeature 47 | // 48 | 49 | static cv::Ptr< AffineInvariantFeature > create(const cv::Ptr< cv::Feature2D > feature, 50 | const double nstripes = -1.) { 51 | return new AffineInvariantFeature(feature, feature, nstripes); 52 | } 53 | 54 | static cv::Ptr< AffineInvariantFeature > create(const cv::Ptr< cv::Feature2D > detector, 55 | const cv::Ptr< cv::Feature2D > extractor, 56 | const double nstripes = -1.) { 57 | return new AffineInvariantFeature(detector, extractor, nstripes); 58 | } 59 | 60 | // 61 | // overloaded functions from AffineInvariantFeatureBase or its base class 62 | // 63 | 64 | virtual void compute(cv::InputArray image, std::vector< cv::KeyPoint > &keypoints, 65 | cv::OutputArray descriptors) { 66 | // extract the input 67 | const cv::Mat image_mat(image.getMat()); 68 | 69 | // prepare outputs of following parallel processing 70 | std::vector< std::vector< cv::KeyPoint > > keypoints_array(ntasks_, keypoints); 71 | std::vector< cv::Mat > descriptors_array(ntasks_); 72 | 73 | // bind each parallel task and arguments 74 | ParallelTasks tasks(ntasks_); 75 | for (std::size_t i = 0; i < ntasks_; ++i) { 76 | tasks[i] = boost::bind(&AffineInvariantFeature::computeTask, this, boost::ref(image_mat), 77 | boost::ref(keypoints_array[i]), boost::ref(descriptors_array[i]), 78 | phi_params_[i], tilt_params_[i]); 79 | } 80 | 81 | // do parallel tasks 82 | cv::parallel_for_(cv::Range(0, ntasks_), tasks, nstripes_); 83 | 84 | // fill the final outputs 85 | extendKeypoints(keypoints_array, keypoints); 86 | extendDescriptors(descriptors_array, descriptors); 87 | } 88 | 89 | virtual void detect(cv::InputArray image, std::vector< cv::KeyPoint > &keypoints, 90 | cv::InputArray mask = cv::noArray()) { 91 | // extract inputs 92 | const cv::Mat image_mat(image.getMat()); 93 | const cv::Mat mask_mat(mask.getMat()); 94 | 95 | // prepare an output of following parallel processing 96 | std::vector< std::vector< cv::KeyPoint > > keypoints_array(ntasks_); 97 | 98 | // bind each parallel task and arguments 99 | ParallelTasks tasks(ntasks_); 100 | for (std::size_t i = 0; i < ntasks_; ++i) { 101 | tasks[i] = boost::bind(&AffineInvariantFeature::detectTask, this, boost::ref(image_mat), 102 | boost::ref(mask_mat), boost::ref(keypoints_array[i]), phi_params_[i], 103 | tilt_params_[i]); 104 | } 105 | 106 | // do parallel tasks 107 | cv::parallel_for_(cv::Range(0, ntasks_), tasks, nstripes_); 108 | 109 | // fill the final output 110 | extendKeypoints(keypoints_array, keypoints); 111 | } 112 | 113 | virtual void detectAndCompute(cv::InputArray image, cv::InputArray mask, 114 | std::vector< cv::KeyPoint > &keypoints, cv::OutputArray descriptors, 115 | bool useProvidedKeypoints = false) { 116 | // just compute descriptors if the keypoints are provided 117 | if (useProvidedKeypoints) { 118 | compute(image, keypoints, descriptors); 119 | return; 120 | } 121 | 122 | // extract inputs 123 | const cv::Mat image_mat(image.getMat()); 124 | const cv::Mat mask_mat(mask.getMat()); 125 | 126 | // prepare outputs of following parallel processing 127 | std::vector< std::vector< cv::KeyPoint > > keypoints_array(ntasks_); 128 | std::vector< cv::Mat > descriptors_array(ntasks_); 129 | 130 | // bind each parallel task and arguments 131 | ParallelTasks tasks(ntasks_); 132 | for (std::size_t i = 0; i < ntasks_; ++i) { 133 | tasks[i] = 134 | boost::bind(&AffineInvariantFeature::detectAndComputeTask, this, boost::ref(image_mat), 135 | boost::ref(mask_mat), boost::ref(keypoints_array[i]), 136 | boost::ref(descriptors_array[i]), phi_params_[i], tilt_params_[i]); 137 | } 138 | 139 | // do parallel tasks 140 | cv::parallel_for_(cv::Range(0, ntasks_), tasks, nstripes_); 141 | 142 | // fill the final outputs 143 | extendKeypoints(keypoints_array, keypoints); 144 | extendDescriptors(descriptors_array, descriptors); 145 | } 146 | 147 | virtual cv::String getDefaultName() const { return "AffineInvariantFeature"; } 148 | 149 | protected: 150 | void computeTask(const cv::Mat &src_image, std::vector< cv::KeyPoint > &keypoints, 151 | cv::Mat &descriptors, const double phi, const double tilt) const { 152 | // apply the affine transformation to the image on the basis of the given parameters 153 | cv::Mat image(src_image.clone()); 154 | cv::Matx23f affine; 155 | warpImage(image, affine, phi, tilt); 156 | 157 | // apply the affine transformation to keypoints 158 | transformKeypoints(keypoints, affine); 159 | 160 | // extract descriptors on the skewed image and keypoints 161 | CV_Assert(extractor_); 162 | extractor_->compute(image, keypoints, descriptors); 163 | 164 | // invert keypoints 165 | invertKeypoints(keypoints, affine); 166 | } 167 | 168 | void detectTask(const cv::Mat &src_image, const cv::Mat &src_mask, 169 | std::vector< cv::KeyPoint > &keypoints, const double phi, 170 | const double tilt) const { 171 | // apply the affine transformation to the image on the basis of the given parameters 172 | cv::Mat image(src_image.clone()); 173 | cv::Matx23f affine; 174 | warpImage(image, affine, phi, tilt); 175 | 176 | // apply the affine transformation to the mask 177 | cv::Mat mask(src_mask.empty() ? cv::Mat(src_image.size(), CV_8UC1, 255) : src_mask.clone()); 178 | warpMask(mask, affine, image.size()); 179 | 180 | // detect keypoints on the skewed image and mask 181 | CV_Assert(detector_); 182 | detector_->detect(image, keypoints, mask); 183 | 184 | // invert keypoints 185 | invertKeypoints(keypoints, affine); 186 | } 187 | 188 | void detectAndComputeTask(const cv::Mat &src_image, const cv::Mat &src_mask, 189 | std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, 190 | const double phi, const double tilt) const { 191 | // apply the affine transformation to the image on the basis of the given parameters 192 | cv::Mat image(src_image.clone()); 193 | cv::Matx23f affine; 194 | warpImage(image, affine, phi, tilt); 195 | 196 | // if keypoints are not provided, first apply the affine transformation to the mask 197 | cv::Mat mask(src_mask.empty() ? cv::Mat(src_image.size(), CV_8UC1, 255) : src_mask.clone()); 198 | warpMask(mask, affine, image.size()); 199 | 200 | // detect keypoints on the skewed image and mask 201 | // and extract descriptors on the image and keypoints 202 | if (detector_ == extractor_) { 203 | CV_Assert(detector_); 204 | detector_->detectAndCompute(image, mask, keypoints, descriptors, false); 205 | } else { 206 | CV_Assert(detector_); 207 | CV_Assert(extractor_); 208 | detector_->detect(image, keypoints, mask); 209 | extractor_->compute(image, keypoints, descriptors); 210 | } 211 | 212 | // invert the positions of the detected keypoints 213 | invertKeypoints(keypoints, affine); 214 | } 215 | 216 | static void warpImage(cv::Mat &image, cv::Matx23f &affine, const double phi, const double tilt) { 217 | // initiate output 218 | affine = cv::Matx23f::eye(); 219 | 220 | if (phi != 0.) { 221 | // rotate the source frame 222 | affine = cv::getRotationMatrix2D(cv::Point2f(0., 0.), phi, 1.); 223 | cv::Rect tmp_rect; 224 | { 225 | std::vector< cv::Point2f > corners(4); 226 | corners[0] = cv::Point2f(0., 0.); 227 | corners[1] = cv::Point2f(image.cols, 0.); 228 | corners[2] = cv::Point2f(image.cols, image.rows); 229 | corners[3] = cv::Point2f(0., image.rows); 230 | std::vector< cv::Point2f > tmp_corners; 231 | cv::transform(corners, tmp_corners, affine); 232 | tmp_rect = cv::boundingRect(tmp_corners); 233 | } 234 | 235 | // cancel the offset of the rotated frame 236 | affine(0, 2) = -tmp_rect.x; 237 | affine(1, 2) = -tmp_rect.y; 238 | 239 | // apply the final transformation to the image 240 | cv::warpAffine(image, image, affine, tmp_rect.size(), cv::INTER_LINEAR, cv::BORDER_REPLICATE); 241 | } 242 | if (tilt != 1.) { 243 | // shrink the image in width 244 | cv::GaussianBlur(image, image, cv::Size(0, 0), 0.8 * std::sqrt(tilt * tilt - 1.), 0.01); 245 | cv::resize(image, image, cv::Size(0, 0), 1. / tilt, 1., cv::INTER_NEAREST); 246 | affine(0, 0) /= tilt; 247 | affine(0, 1) /= tilt; 248 | affine(0, 2) /= tilt; 249 | } 250 | } 251 | 252 | static void warpMask(cv::Mat &mask, const cv::Matx23f &affine, const cv::Size size) { 253 | if (affine == cv::Matx23f::eye()) { 254 | return; 255 | } 256 | cv::warpAffine(mask, mask, affine, size, cv::INTER_NEAREST); 257 | } 258 | 259 | static void transformKeypoints(std::vector< cv::KeyPoint > &keypoints, 260 | const cv::Matx23f &affine) { 261 | if (affine == cv::Matx23f::eye()) { 262 | return; 263 | } 264 | for (std::vector< cv::KeyPoint >::iterator keypoint = keypoints.begin(); 265 | keypoint != keypoints.end(); ++keypoint) { 266 | // convert cv::Point2f to cv::Mat (1x1,2ch) without copying data. 267 | // this is required because cv::transform does not accept cv::Point2f. 268 | cv::Mat pt(cv::Mat(keypoint->pt, false).reshape(2)); 269 | cv::transform(pt, pt, affine); 270 | } 271 | } 272 | 273 | static void invertKeypoints(std::vector< cv::KeyPoint > &keypoints, const cv::Matx23f &affine) { 274 | if (affine == cv::Matx23f::eye()) { 275 | return; 276 | } 277 | cv::Matx23f invert_affine; 278 | cv::invertAffineTransform(affine, invert_affine); 279 | transformKeypoints(keypoints, invert_affine); 280 | } 281 | 282 | static void extendKeypoints(const std::vector< std::vector< cv::KeyPoint > > &src, 283 | std::vector< cv::KeyPoint > &dst) { 284 | dst.clear(); 285 | for (std::size_t i = 0; i < src.size(); ++i) { 286 | dst.insert(dst.end(), src[i].begin(), src[i].end()); 287 | } 288 | } 289 | 290 | void extendDescriptors(const std::vector< cv::Mat > &src, cv::OutputArray dst) const { 291 | // create the output array 292 | int nrows(0); 293 | for (std::size_t i = 0; i < src.size(); ++i) { 294 | nrows += src[i].rows; 295 | } 296 | dst.create(nrows, descriptorSize(), descriptorType()); 297 | 298 | // fill the output array 299 | cv::Mat dst_mat(dst.getMat()); 300 | int rows(0); 301 | for (std::size_t i = 0; i < src.size(); ++i) { 302 | if (src[i].rows > 0) { 303 | src[i].copyTo(dst_mat.rowRange(rows, rows + src[i].rows)); 304 | rows += src[i].rows; 305 | } 306 | } 307 | } 308 | 309 | protected: 310 | std::vector< double > phi_params_; 311 | std::vector< double > tilt_params_; 312 | std::size_t ntasks_; 313 | const double nstripes_; 314 | }; 315 | 316 | } // namespace affine_invariant_features 317 | 318 | #endif --------------------------------------------------------------------------------