diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 038bc46ef2bbaae00cdf63086b38c19216d5dbc6..780d6fe7dc23829285b855aef8d31c30076d820d 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -40,6 +40,8 @@ SET(sources descriptors/brisk/descriptor_brisk_load_yaml.cpp descriptors/kaze/descriptor_kaze.cpp descriptors/kaze/descriptor_kaze_load_yaml.cpp + descriptors/akaze/descriptor_akaze.cpp + descriptors/akaze/descriptor_akaze_load_yaml.cpp matchers/matcher_base.cpp ) # application header files @@ -70,6 +72,7 @@ SET(headers descriptors/surf/descriptor_surf.h descriptors/brisk/descriptor_brisk.h descriptors/kaze/descriptor_kaze.h + descriptors/akaze/descriptor_akaze.h matchers/matcher_factory.h matchers/matcher_base.h) diff --git a/src/descriptors/akaze/descriptor_akaze.cpp b/src/descriptors/akaze/descriptor_akaze.cpp new file mode 100644 index 0000000000000000000000000000000000000000..db9bdc6d5f44afd301f83d732976706e0af66546 --- /dev/null +++ b/src/descriptors/akaze/descriptor_akaze.cpp @@ -0,0 +1,17 @@ +#include "descriptor_akaze.h" + +namespace vision_utils { + +DescriptorAKAZE::DescriptorAKAZE(void) +{} + +DescriptorAKAZE::~DescriptorAKAZE(void) +{} + +} /* namespace vision_utils */ + +// Register in the DescriptorsFactory +namespace vision_utils +{ +VU_REGISTER_DESCRIPTOR("AKAZE", DescriptorAKAZE); +} /* namespace vision_utils */ diff --git a/src/descriptors/akaze/descriptor_akaze.h b/src/descriptors/akaze/descriptor_akaze.h new file mode 100644 index 0000000000000000000000000000000000000000..11979d7ec0f9ba4199da372f09edbec8b3e4df60 --- /dev/null +++ b/src/descriptors/akaze/descriptor_akaze.h @@ -0,0 +1,79 @@ +#ifndef _DESCRIPTOR_AKAZE_H_ +#define _DESCRIPTOR_AKAZE_H_ + +#include "../descriptor_base.h" +#include "../descriptor_factory.h" + +// yaml-cpp library +#ifdef USING_YAML + #include <yaml-cpp/yaml.h> +#endif + +namespace vision_utils { + +// Create all pointers +VU_PTR_TYPEDEFS(DescriptorAKAZE); +VU_PTR_TYPEDEFS(DescriptorParamsAKAZE); + +/** \brief Class parameters + * + */ +struct DescriptorParamsAKAZE: public ParamsBase +{ + int descriptor_type = cv::AKAZE::DESCRIPTOR_MLDB; // Type of the extracted descriptor. DESCRIPTOR_KAZE_UPRIGHT=2, DESCRIPTOR_KAZE=3, DESCRIPTOR_MLDB_UPRIGHT=4, DESCRIPTOR_MLDB=5 + int descriptor_size = 0; // Size of the descriptor in bits. 0 -> Full size + int descriptor_channels = 3; // Number of channels in the descriptor (1, 2, 3) + float threshold = 0.001f; // Descriptor response threshold to accept point + int nOctaves = 4; // Maximum octave evolution of the image + int nOctaveLayers = 4; // Default number of sublevels per scale level + int diffusivity = cv::KAZE::DIFF_PM_G2; // Diffusivity type. DIFF_PM_G1=0, DIFF_PM_G2=1, DIFF_WEICKERT=2, DIFF_CHARBONNIER=3 +}; + +/** \brief DETECTOR class + * + */ +class DescriptorAKAZE : public DescriptorBase { + + public: + DescriptorAKAZE(); + virtual ~DescriptorAKAZE(void); + + // Factory method + static DescriptorBasePtr create(const std::string& _unique_name, const ParamsBasePtr _params); + + private: + + void defineDescriptor(const ParamsBasePtr _params); +}; + +/* + * brief Define detector + */ +inline void DescriptorAKAZE::defineDescriptor(const ParamsBasePtr _params) +{ + DescriptorParamsAKAZEPtr params_ptr = std::static_pointer_cast<DescriptorParamsAKAZE>(_params); + + descriptor_ = cv::AKAZE::create(params_ptr->descriptor_type, + params_ptr->descriptor_size, + params_ptr->descriptor_channels, + params_ptr->threshold, + params_ptr->nOctaves, + params_ptr->nOctaveLayers, + params_ptr->diffusivity); +} + + +/* + * brief Create object in factory + */ +inline DescriptorBasePtr DescriptorAKAZE::create(const std::string& _unique_name, const ParamsBasePtr _params) +{ + DescriptorAKAZEPtr det_ptr = std::make_shared<DescriptorAKAZE>(); + det_ptr->setName(_unique_name); + det_ptr->defineDescriptor(_params); + return det_ptr; +} + +} /* namespace vision_utils */ + +#endif /* _DESCRIPTOR_AKAZE_H_ */ diff --git a/src/descriptors/akaze/descriptor_akaze_load_yaml.cpp b/src/descriptors/akaze/descriptor_akaze_load_yaml.cpp new file mode 100644 index 0000000000000000000000000000000000000000..043ceb070a7a93f2cc7e496674afa8495fbe199a --- /dev/null +++ b/src/descriptors/akaze/descriptor_akaze_load_yaml.cpp @@ -0,0 +1,51 @@ +#include "descriptor_akaze.h" + +#ifdef USING_YAML + +// yaml-cpp library +#include <yaml-cpp/yaml.h> + +namespace vision_utils +{ + +namespace +{ + +static ParamsBasePtr createParamsAKAZEDescriptor(const std::string & _filename_dot_yaml) +{ + DescriptorParamsAKAZEPtr params_ptr = std::make_shared<DescriptorParamsAKAZE>(); + + using std::string; + using YAML::Node; + Node yaml_params = YAML::LoadFile(_filename_dot_yaml); + if (!yaml_params.IsNull()) + { + Node d_yaml = yaml_params["descriptor"]; + if(d_yaml["type"].as<string>() == "AKAZE") + { + params_ptr->descriptor_type = d_yaml["descriptor_type"].as<int>(); + params_ptr->descriptor_size = d_yaml["descriptor_size"].as<int>(); + params_ptr->descriptor_channels = d_yaml["descriptor_channels"].as<int>(); + params_ptr->threshold = d_yaml["threshold"].as<float>(); + params_ptr->nOctaves = d_yaml["nOctaves"].as<int>(); + params_ptr->nOctaveLayers = d_yaml["nOctaveLayers"].as<int>(); + params_ptr->diffusivity = d_yaml["diffusivity"].as<int>(); + }else + { + std::cerr << "Bad configuration file. Wrong type " << d_yaml["type"].as<string>() << std::endl; + return nullptr; + } + } + + return params_ptr; +} + +// Register in the SensorFactory +const bool registered_desAKAZE_params = ParamsFactory::get().registerCreator("AKAZE DES", createParamsAKAZEDescriptor); + +} /* namespace [unnamed] */ + +} /* namespace vision_utils */ + +#endif /* IF USING_YAML */ + diff --git a/src/descriptors/brisk/descriptor_brisk.cpp b/src/descriptors/brisk/descriptor_brisk.cpp index 6cd02d5d33959dc349f107dbf0362476d4b5cd3d..55c9f5e6e2a3f1b2ace9d08d70b1f4b4bbd1be1d 100644 --- a/src/descriptors/brisk/descriptor_brisk.cpp +++ b/src/descriptors/brisk/descriptor_brisk.cpp @@ -13,5 +13,5 @@ DescriptorBRISK::~DescriptorBRISK(void) // Register in the DescriptorsFactory namespace vision_utils { -VU_REGISTER_DESCRIPTOR("BRISK DES", DescriptorBRISK); +VU_REGISTER_DESCRIPTOR("BRISK", DescriptorBRISK); } /* namespace vision_utils */ diff --git a/src/descriptors/brisk/descriptor_brisk_load_yaml.cpp b/src/descriptors/brisk/descriptor_brisk_load_yaml.cpp index 2ba8d972e67fb7e567d182e57db41a83aa899ed6..394084b47ae57956906f96715b10e3f5b258137f 100644 --- a/src/descriptors/brisk/descriptor_brisk_load_yaml.cpp +++ b/src/descriptors/brisk/descriptor_brisk_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsBRISKDescriptor(const std::string & _filename_d if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["descriptor"]; - if(d_yaml["type"].as<string>() == "BRISK DES") + if(d_yaml["type"].as<string>() == "BRISK") { params_ptr->thresh = d_yaml["thresh"].as<int>(); params_ptr->octaves = d_yaml["octaves"].as<int>(); diff --git a/src/descriptors/descriptor_base.cpp b/src/descriptors/descriptor_base.cpp index 4af05bab47e7400607331cc1fee39c31b9744536..af912459197525ab6a6b5ffaa698cce27107083f 100644 --- a/src/descriptors/descriptor_base.cpp +++ b/src/descriptors/descriptor_base.cpp @@ -38,7 +38,7 @@ DescriptorBasePtr setupDescriptor(const std::string& _type, const std::string& _ #ifdef USING_YAML DescriptorBasePtr setupDescriptor(const std::string& _type, const std::string& _unique_name, const std::string& _filename_dot_yaml) { - ParamsBasePtr params_ptr = ParamsFactory::get().create(_type, _filename_dot_yaml); + ParamsBasePtr params_ptr = ParamsFactory::get().create(_type+" DES", _filename_dot_yaml); return setupDescriptor(_type, _unique_name, params_ptr); } #endif diff --git a/src/descriptors/kaze/descriptor_kaze.cpp b/src/descriptors/kaze/descriptor_kaze.cpp index 885cffe75ab704b211b01683a36e405eef1b405e..2cd80cba238a9efd120d0efa8ffd81237cbb6f5c 100644 --- a/src/descriptors/kaze/descriptor_kaze.cpp +++ b/src/descriptors/kaze/descriptor_kaze.cpp @@ -13,5 +13,5 @@ DescriptorKAZE::~DescriptorKAZE(void) // Register in the DescriptorsFactory namespace vision_utils { -VU_REGISTER_DESCRIPTOR("KAZE DES", DescriptorKAZE); +VU_REGISTER_DESCRIPTOR("KAZE", DescriptorKAZE); } /* namespace vision_utils */ diff --git a/src/descriptors/kaze/descriptor_kaze_load_yaml.cpp b/src/descriptors/kaze/descriptor_kaze_load_yaml.cpp index 28b39e206540444d438cbe200b35cd7861da3c6b..63fd5edd7e2605a0e51bf23fdadbafdc7365de53 100644 --- a/src/descriptors/kaze/descriptor_kaze_load_yaml.cpp +++ b/src/descriptors/kaze/descriptor_kaze_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsKAZEDescriptor(const std::string & _filename_do if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["descriptor"]; - if(d_yaml["type"].as<string>() == "KAZE DES") + if(d_yaml["type"].as<string>() == "KAZE") { params_ptr->extended = d_yaml["extended"].as<bool>(); params_ptr->upright = d_yaml["upright"].as<bool>(); diff --git a/src/descriptors/orb/descriptor_orb.cpp b/src/descriptors/orb/descriptor_orb.cpp index 0fee08919d8b5456079e06e0b507b68d5f6d8f33..88d2552e5745281e4fc799dc7401eaa0b1ac8c51 100644 --- a/src/descriptors/orb/descriptor_orb.cpp +++ b/src/descriptors/orb/descriptor_orb.cpp @@ -13,5 +13,5 @@ DescriptorORB::~DescriptorORB(void) // Register in the DescriptorsFactory namespace vision_utils { -VU_REGISTER_DESCRIPTOR("ORB DES", DescriptorORB); +VU_REGISTER_DESCRIPTOR("ORB", DescriptorORB); } /* namespace vision_utils */ diff --git a/src/descriptors/orb/descriptor_orb_load_yaml.cpp b/src/descriptors/orb/descriptor_orb_load_yaml.cpp index c8cc632996b202479488064c5da3a97470482e47..03b31f79acbe18758efa19c0e3da88bd06a4d319 100644 --- a/src/descriptors/orb/descriptor_orb_load_yaml.cpp +++ b/src/descriptors/orb/descriptor_orb_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsORBDescriptor(const std::string & _filename_dot if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["descriptor"]; - if(d_yaml["type"].as<string>() == "ORB DES") + if(d_yaml["type"].as<string>() == "ORB") { params_ptr->nfeatures = d_yaml["nfeatures"].as<unsigned int>(); params_ptr->scaleFactor = d_yaml["scale factor"].as<float>(); diff --git a/src/descriptors/sift/descriptor_sift.cpp b/src/descriptors/sift/descriptor_sift.cpp index e14f8a6408718806d3950164239a83ca9a982e4a..905fc58832237f3b46fb9f99d9bf498652b41c80 100644 --- a/src/descriptors/sift/descriptor_sift.cpp +++ b/src/descriptors/sift/descriptor_sift.cpp @@ -13,5 +13,5 @@ DescriptorSIFT::~DescriptorSIFT(void) // Register in the DescriptorsFactory namespace vision_utils { -VU_REGISTER_DESCRIPTOR("SIFT DES", DescriptorSIFT); +VU_REGISTER_DESCRIPTOR("SIFT", DescriptorSIFT); } /* namespace vision_utils */ diff --git a/src/descriptors/sift/descriptor_sift_load_yaml.cpp b/src/descriptors/sift/descriptor_sift_load_yaml.cpp index 0a0f202ba38d418d75c2296c93020f270000f685..d18646e1859e87b7bd22c5d2d32b02d907ed80df 100644 --- a/src/descriptors/sift/descriptor_sift_load_yaml.cpp +++ b/src/descriptors/sift/descriptor_sift_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsSIFTDescriptor(const std::string & _filename_do if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["descriptor"]; - if(d_yaml["type"].as<string>() == "SIFT DES") + if(d_yaml["type"].as<string>() == "SIFT") { params_ptr->nfeatures = d_yaml["nfeatures"].as<int>(); params_ptr->nOctaveLayers = d_yaml["nOctaveLayers"].as<int>(); @@ -30,7 +30,7 @@ static ParamsBasePtr createParamsSIFTDescriptor(const std::string & _filename_do params_ptr->sigma = d_yaml["sigma"].as<double>(); }else { - std::cerr << "Bad configuration file. Wrong type " << d_yaml["type"].as<string>() << std::endl; + std::cerr << "DESCRIPTOR Bad configuration file. Wrong type " << d_yaml["type"].as<string>() << std::endl; return nullptr; } } diff --git a/src/descriptors/surf/descriptor_surf.cpp b/src/descriptors/surf/descriptor_surf.cpp index ec6df829331fa120f8f2800affdc690379e8d37b..6e7d7a462c065bd0f17b09d4de6345718db77884 100644 --- a/src/descriptors/surf/descriptor_surf.cpp +++ b/src/descriptors/surf/descriptor_surf.cpp @@ -13,5 +13,5 @@ DescriptorSURF::~DescriptorSURF(void) // Register in the DescriptorsFactory namespace vision_utils { -VU_REGISTER_DESCRIPTOR("SURF DES", DescriptorSURF); +VU_REGISTER_DESCRIPTOR("SURF", DescriptorSURF); } /* namespace vision_utils */ diff --git a/src/descriptors/surf/descriptor_surf_load_yaml.cpp b/src/descriptors/surf/descriptor_surf_load_yaml.cpp index dab0495dec261360262254ecdf8d52d2e1049182..8cfb642ed31e728f97e5f26bc8fcb4d9e34249e0 100644 --- a/src/descriptors/surf/descriptor_surf_load_yaml.cpp +++ b/src/descriptors/surf/descriptor_surf_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsSURFDescriptor(const std::string & _filename_do if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["descriptor"]; - if(d_yaml["type"].as<string>() == "SURF DES") + if(d_yaml["type"].as<string>() == "SURF") { params_ptr->hessianThreshold = d_yaml["hessianThreshold"].as<double>(); params_ptr->nOctaves = d_yaml["nOctaves"].as<int>(); diff --git a/src/detectors/agast/detector_agast.cpp b/src/detectors/agast/detector_agast.cpp index 658439519b3f38010ef313030437d1b1a49b076d..9bcfbe1cf487cf4ae681e4ecf74bdbc18ed440bc 100644 --- a/src/detectors/agast/detector_agast.cpp +++ b/src/detectors/agast/detector_agast.cpp @@ -13,5 +13,5 @@ DetectorAGAST::~DetectorAGAST(void) // Register in the DetectorsFactory namespace vision_utils { -VU_REGISTER_DETECTOR("AGAST DET", DetectorAGAST); +VU_REGISTER_DETECTOR("AGAST", DetectorAGAST); } /* namespace vision_utils */ diff --git a/src/detectors/agast/detector_agast_load_yaml.cpp b/src/detectors/agast/detector_agast_load_yaml.cpp index 907b2650992fd0981d2d624d1f27edcc62985978..e07e11706c0ede2b3aa452ed2973985c66fe7ea2 100644 --- a/src/detectors/agast/detector_agast_load_yaml.cpp +++ b/src/detectors/agast/detector_agast_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsAGASTDetector(const std::string & _filename_dot if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["detector"]; - if(d_yaml["type"].as<string>() == "AGAST DET") + if(d_yaml["type"].as<string>() == "AGAST") { params_ptr->threshold = d_yaml["threshold"].as<int>(); params_ptr->nonmaxSuppression = d_yaml["nonmaxSuppression"].as<bool>(); diff --git a/src/detectors/akaze/detector_akaze.cpp b/src/detectors/akaze/detector_akaze.cpp index f40a9299774299d40ad6df675ec4664dd9ac031d..9b7e0aaa9953816f0661ac9fd048d5807d2f2fdd 100644 --- a/src/detectors/akaze/detector_akaze.cpp +++ b/src/detectors/akaze/detector_akaze.cpp @@ -13,5 +13,5 @@ DetectorAKAZE::~DetectorAKAZE(void) // Register in the DetectorsFactory namespace vision_utils { -VU_REGISTER_DETECTOR("AKAZE DET", DetectorAKAZE); +VU_REGISTER_DETECTOR("AKAZE", DetectorAKAZE); } /* namespace vision_utils */ diff --git a/src/detectors/akaze/detector_akaze_load_yaml.cpp b/src/detectors/akaze/detector_akaze_load_yaml.cpp index 0f4e9bd61c4846c2a06af84ccca9d804f84cc590..1f41c7cd508ee3b39d50e89be7a1e6718e7fd4e8 100644 --- a/src/detectors/akaze/detector_akaze_load_yaml.cpp +++ b/src/detectors/akaze/detector_akaze_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsAKAZEDetector(const std::string & _filename_dot if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["detector"]; - if(d_yaml["type"].as<string>() == "AKAZE DET") + if(d_yaml["type"].as<string>() == "AKAZE") { params_ptr->descriptor_type = d_yaml["descriptor_type"].as<int>(); params_ptr->descriptor_size = d_yaml["descriptor_size"].as<int>(); diff --git a/src/detectors/brisk/detector_brisk.cpp b/src/detectors/brisk/detector_brisk.cpp index 875bc73143b3635da10940f3cd640e349b84c960..d7bfc3ee2fb26e2904945fe0a53d873770beafc4 100644 --- a/src/detectors/brisk/detector_brisk.cpp +++ b/src/detectors/brisk/detector_brisk.cpp @@ -13,5 +13,5 @@ DetectorBRISK::~DetectorBRISK(void) // Register in the DetectorsFactory namespace vision_utils { -VU_REGISTER_DETECTOR("BRISK DET", DetectorBRISK); +VU_REGISTER_DETECTOR("BRISK", DetectorBRISK); } /* namespace vision_utils */ diff --git a/src/detectors/brisk/detector_brisk_load_yaml.cpp b/src/detectors/brisk/detector_brisk_load_yaml.cpp index e8766f6346ca4219e7905861da4fc2df7135ac4c..dd4317c7a2bae16171614f102f995fb1d23d7462 100644 --- a/src/detectors/brisk/detector_brisk_load_yaml.cpp +++ b/src/detectors/brisk/detector_brisk_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsBRISKDetector(const std::string & _filename_dot if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["detector"]; - if(d_yaml["type"].as<string>() == "BRISK DET") + if(d_yaml["type"].as<string>() == "BRISK") { params_ptr->thresh = d_yaml["thresh"].as<int>(); params_ptr->octaves = d_yaml["octaves"].as<int>(); diff --git a/src/detectors/detector_base.cpp b/src/detectors/detector_base.cpp index 45801e3829b61d79edd5889cb811d8e66b46d41d..2b6e87eac33c50bb66b0384d94d622866eb0a916 100644 --- a/src/detectors/detector_base.cpp +++ b/src/detectors/detector_base.cpp @@ -41,7 +41,7 @@ DetectorBasePtr setupDetector(const std::string& _type, const std::string& _uniq #ifdef USING_YAML DetectorBasePtr setupDetector(const std::string& _type, const std::string& _unique_name, const std::string& _filename_dot_yaml) { - ParamsBasePtr params_ptr = ParamsFactory::get().create(_type, _filename_dot_yaml); + ParamsBasePtr params_ptr = ParamsFactory::get().create(_type+" DET", _filename_dot_yaml); return setupDetector(_type, _unique_name, params_ptr); } #endif diff --git a/src/detectors/fast/detector_fast.cpp b/src/detectors/fast/detector_fast.cpp index 380482f04ea161f71ee2182b1dd1c260dfa663c7..5410bb62c1f07889489d0f20337086916be119f4 100644 --- a/src/detectors/fast/detector_fast.cpp +++ b/src/detectors/fast/detector_fast.cpp @@ -13,5 +13,5 @@ DetectorFAST::~DetectorFAST(void) // Register in the DetectorsFactory namespace vision_utils { -VU_REGISTER_DETECTOR("FAST DET", DetectorFAST); +VU_REGISTER_DETECTOR("FAST", DetectorFAST); } /* namespace vision_utils */ diff --git a/src/detectors/fast/detector_fast_load_yaml.cpp b/src/detectors/fast/detector_fast_load_yaml.cpp index b84d355b16b15b9b236a7022b2cdf9aab52a349b..130e717be820c35304e2ae2e41adbc45c8cca2ba 100644 --- a/src/detectors/fast/detector_fast_load_yaml.cpp +++ b/src/detectors/fast/detector_fast_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsFASTDetector(const std::string & _filename_dot_ if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["detector"]; - if(d_yaml["type"].as<string>() == "FAST DET") + if(d_yaml["type"].as<string>() == "FAST") { params_ptr->threshold = d_yaml["threshold"].as<int>(); params_ptr->nonmaxSuppression = d_yaml["nonmaxSuppression"].as<bool>(); diff --git a/src/detectors/gftt/detector_gftt.cpp b/src/detectors/gftt/detector_gftt.cpp index 6fdcf07a8fdc312f136dc1565d6b2f09d45701e9..a00ba7debdfd38e696ae8a1764cf168e5aa790be 100644 --- a/src/detectors/gftt/detector_gftt.cpp +++ b/src/detectors/gftt/detector_gftt.cpp @@ -13,5 +13,5 @@ DetectorGFTT::~DetectorGFTT(void) // Register in the DetectorsFactory namespace vision_utils { -VU_REGISTER_DETECTOR("GFTT DET", DetectorGFTT); +VU_REGISTER_DETECTOR("GFTT", DetectorGFTT); } /* namespace vision_utils */ diff --git a/src/detectors/gftt/detector_gftt_load_yaml.cpp b/src/detectors/gftt/detector_gftt_load_yaml.cpp index 7e48ae40cf1b690e72a7da770b06dd219b83b6ca..1b0931131fc2b5f762a5b93aeedae5b83c480cc2 100644 --- a/src/detectors/gftt/detector_gftt_load_yaml.cpp +++ b/src/detectors/gftt/detector_gftt_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsGFTTDetector(const std::string & _filename_dot_ if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["detector"]; - if(d_yaml["type"].as<string>() == "GFTT DET") + if(d_yaml["type"].as<string>() == "GFTT") { params_ptr->maxCorners = d_yaml["maxCorners"].as<int>(); params_ptr->qualityLevel = d_yaml["qualityLevel"].as<double>(); diff --git a/src/detectors/harris/detector_harris.cpp b/src/detectors/harris/detector_harris.cpp index 410189edcba7b0557d4253ddf3f6e80bc589fa58..7af88f690e755f1bc2d4987ac57a8cb3c4c66271 100644 --- a/src/detectors/harris/detector_harris.cpp +++ b/src/detectors/harris/detector_harris.cpp @@ -13,5 +13,5 @@ DetectorHARRIS::~DetectorHARRIS(void) // Register in the DetectorsFactory namespace vision_utils { -VU_REGISTER_DETECTOR("HARRIS DET", DetectorHARRIS); +VU_REGISTER_DETECTOR("HARRIS", DetectorHARRIS); } /* namespace vision_utils */ diff --git a/src/detectors/harris/detector_harris_load_yaml.cpp b/src/detectors/harris/detector_harris_load_yaml.cpp index a819993ccaa129e52adbcb51b59acec38f5489c6..41127275b18e0d057445a8a7ddc73c447ad9bcdc 100644 --- a/src/detectors/harris/detector_harris_load_yaml.cpp +++ b/src/detectors/harris/detector_harris_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsHARRISDetector(const std::string & _filename_do if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["detector"]; - if(d_yaml["type"].as<string>() == "HARRIS DET") + if(d_yaml["type"].as<string>() == "HARRIS") { params_ptr->maxCorners = d_yaml["maxCorners"].as<int>(); params_ptr->qualityLevel = d_yaml["qualityLevel"].as<double>(); diff --git a/src/detectors/kaze/detector_kaze.cpp b/src/detectors/kaze/detector_kaze.cpp index cfbc23abf5354cdf8cde5de89fb6ff948519a32e..7154cbb1b877e79be6ff296faf2fea4901548811 100644 --- a/src/detectors/kaze/detector_kaze.cpp +++ b/src/detectors/kaze/detector_kaze.cpp @@ -13,5 +13,5 @@ DetectorKAZE::~DetectorKAZE(void) // Register in the DetectorsFactory namespace vision_utils { -VU_REGISTER_DETECTOR("KAZE DET", DetectorKAZE); +VU_REGISTER_DETECTOR("KAZE", DetectorKAZE); } /* namespace vision_utils */ diff --git a/src/detectors/kaze/detector_kaze_load_yaml.cpp b/src/detectors/kaze/detector_kaze_load_yaml.cpp index 8fd87c424504ccb1c74b727cb7f9c750804e64ea..b53d642f4755fa0d2ffe5e86a4889378b487c9d8 100644 --- a/src/detectors/kaze/detector_kaze_load_yaml.cpp +++ b/src/detectors/kaze/detector_kaze_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsKAZEDetector(const std::string & _filename_dot_ if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["detector"]; - if(d_yaml["type"].as<string>() == "KAZE DET") + if(d_yaml["type"].as<string>() == "KAZE") { params_ptr->extended = d_yaml["extended"].as<bool>(); params_ptr->upright = d_yaml["upright"].as<bool>(); diff --git a/src/detectors/mser/detector_mser.cpp b/src/detectors/mser/detector_mser.cpp index 2859f8a2cc459f43f4cd7a1c40758790f1c5127a..98c0af8f33f723b3e6f21053e24a566d08377054 100644 --- a/src/detectors/mser/detector_mser.cpp +++ b/src/detectors/mser/detector_mser.cpp @@ -13,5 +13,5 @@ DetectorMSER::~DetectorMSER(void) // Register in the DetectorsFactory namespace vision_utils { -VU_REGISTER_DETECTOR("MSER DET", DetectorMSER); +VU_REGISTER_DETECTOR("MSER", DetectorMSER); } /* namespace vision_utils */ diff --git a/src/detectors/mser/detector_mser_load_yaml.cpp b/src/detectors/mser/detector_mser_load_yaml.cpp index 10642f78e83137e67b3fc58a1bb13aeb85cb12b5..bbe4960943d2dfe827b196254e93eb4fd437d30b 100644 --- a/src/detectors/mser/detector_mser_load_yaml.cpp +++ b/src/detectors/mser/detector_mser_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsMSERDetector(const std::string & _filename_dot_ if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["detector"]; - if(d_yaml["type"].as<string>() == "MSER DET") + if(d_yaml["type"].as<string>() == "MSER") { params_ptr->delta = d_yaml["delta"].as<int>(); params_ptr->min_area = d_yaml["min_area"].as<int>(); diff --git a/src/detectors/orb/detector_orb.cpp b/src/detectors/orb/detector_orb.cpp index 402dfb5b2c852f24ec2da34431582bf5c1834337..d30d1331204e8621e173bde8a8a9c868cdc9c36d 100644 --- a/src/detectors/orb/detector_orb.cpp +++ b/src/detectors/orb/detector_orb.cpp @@ -13,5 +13,5 @@ DetectorORB::~DetectorORB(void) // Register in the DetectorsFactory namespace vision_utils { -VU_REGISTER_DETECTOR("ORB DET", DetectorORB); +VU_REGISTER_DETECTOR("ORB", DetectorORB); } /* namespace vision_utils */ diff --git a/src/detectors/orb/detector_orb_load_yaml.cpp b/src/detectors/orb/detector_orb_load_yaml.cpp index 485c9ee9e601b875ab31b403b281daa4df268b85..84a5ba3fcf5f2fbe434c641f328b49080a17186b 100644 --- a/src/detectors/orb/detector_orb_load_yaml.cpp +++ b/src/detectors/orb/detector_orb_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsORBDetector(const std::string & _filename_dot_y if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["detector"]; - if(d_yaml["type"].as<string>() == "ORB DET") + if(d_yaml["type"].as<string>() == "ORB") { params_ptr->nfeatures = d_yaml["nfeatures"].as<unsigned int>(); params_ptr->scaleFactor = d_yaml["scale factor"].as<float>(); diff --git a/src/detectors/sbd/detector_sbd.cpp b/src/detectors/sbd/detector_sbd.cpp index 5f80fea0d1d6bcd6c0f62973aa80d0eb607f8982..8ec56fb210b117d78af3af966fd274841b2cf71d 100644 --- a/src/detectors/sbd/detector_sbd.cpp +++ b/src/detectors/sbd/detector_sbd.cpp @@ -13,5 +13,5 @@ DetectorSBD::~DetectorSBD(void) // Register in the DetectorsFactory namespace vision_utils { -VU_REGISTER_DETECTOR("SBD DET", DetectorSBD); +VU_REGISTER_DETECTOR("SBD", DetectorSBD); } /* namespace vision_utils */ diff --git a/src/detectors/sbd/detector_sbd_load_yaml.cpp b/src/detectors/sbd/detector_sbd_load_yaml.cpp index adcbf8a40d818dd8e127a29b7cefc2b367d4079e..c0abc6998abef514d7c02772adb1d2ceb372ef19 100644 --- a/src/detectors/sbd/detector_sbd_load_yaml.cpp +++ b/src/detectors/sbd/detector_sbd_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsSBDDetector(const std::string & _filename_dot_y if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["detector"]; - if(d_yaml["type"].as<string>() == "SBD DET") + if(d_yaml["type"].as<string>() == "SBD") { params_ptr->cv_params.thresholdStep = d_yaml["thresholdStep"].as<float>(); params_ptr->cv_params.minThreshold = d_yaml["minThreshold"].as<float>(); diff --git a/src/detectors/sift/detector_sift.cpp b/src/detectors/sift/detector_sift.cpp index 770ca9051d69f08caf706a8866641c56f71bcf81..547ece8bfd82907c0962aa2855dd243577de66b2 100644 --- a/src/detectors/sift/detector_sift.cpp +++ b/src/detectors/sift/detector_sift.cpp @@ -13,5 +13,5 @@ DetectorSIFT::~DetectorSIFT(void) // Register in the DetectorsFactory namespace vision_utils { -VU_REGISTER_DETECTOR("SIFT DET", DetectorSIFT); +VU_REGISTER_DETECTOR("SIFT", DetectorSIFT); } /* namespace vision_utils */ diff --git a/src/detectors/sift/detector_sift_load_yaml.cpp b/src/detectors/sift/detector_sift_load_yaml.cpp index dce5b421a280e7a477a6f10eef404e61185a60a5..9e4f7b1aafccd4514d841b134dc0809ff7c6ee8a 100644 --- a/src/detectors/sift/detector_sift_load_yaml.cpp +++ b/src/detectors/sift/detector_sift_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsSIFTDetector(const std::string & _filename_dot_ if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["detector"]; - if(d_yaml["type"].as<string>() == "SIFT DET") + if(d_yaml["type"].as<string>() == "SIFT") { params_ptr->nfeatures = d_yaml["nfeatures"].as<int>(); params_ptr->nOctaveLayers = d_yaml["nOctaveLayers"].as<int>(); diff --git a/src/detectors/surf/detector_surf.cpp b/src/detectors/surf/detector_surf.cpp index ed7a4350e650614ff92b3a27fef54dd803282d7d..65c50310145d37429407059f8cbb64d87844f7da 100644 --- a/src/detectors/surf/detector_surf.cpp +++ b/src/detectors/surf/detector_surf.cpp @@ -13,5 +13,5 @@ DetectorSURF::~DetectorSURF(void) // Register in the DetectorsFactory namespace vision_utils { -VU_REGISTER_DETECTOR("SURF DET", DetectorSURF); +VU_REGISTER_DETECTOR("SURF", DetectorSURF); } /* namespace vision_utils */ diff --git a/src/detectors/surf/detector_surf_load_yaml.cpp b/src/detectors/surf/detector_surf_load_yaml.cpp index 47907065a853b4f4f0a8154f85749eea57b7d841..1cd84e8d30d47f8e13b588bccda5dc0214e1cc46 100644 --- a/src/detectors/surf/detector_surf_load_yaml.cpp +++ b/src/detectors/surf/detector_surf_load_yaml.cpp @@ -21,7 +21,7 @@ static ParamsBasePtr createParamsSURFDetector(const std::string & _filename_dot_ if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["detector"]; - if(d_yaml["type"].as<string>() == "SURF DET") + if(d_yaml["type"].as<string>() == "SURF") { params_ptr->hessianThreshold = d_yaml["hessianThreshold"].as<double>(); params_ptr->nOctaves = d_yaml["nOctaves"].as<int>(); diff --git a/src/examples/test_descriptor.cpp b/src/examples/test_descriptor.cpp index e1695463fce4c8c74232ebc88341d4b83cee27f9..6a27f49b371c242722633e85bcc14c12292f0a39 100644 --- a/src/examples/test_descriptor.cpp +++ b/src/examples/test_descriptor.cpp @@ -27,7 +27,7 @@ #include "../descriptors/surf/descriptor_surf.h" #include "../descriptors/brisk/descriptor_brisk.h" #include "../descriptors/kaze/descriptor_kaze.h" -//#include "../descriptors/akaze/descriptor_akaze.h" +#include "../descriptors/akaze/descriptor_akaze.h" //#include "../descriptors/latch/descriptor_latch.h" //#include "../descriptors/freak/descriptor_freak.h" //#include "../descriptors/brief/descriptor_brief.h" @@ -48,69 +48,69 @@ int main(void) std::string vu_root = _VU_ROOT_DIR; // Setup camera sensor by default - SensorBasePtr sen_b_ptr = setupSensor("USB CAM", "CAMERA test", vu_root + path_yaml_file + "/FAST.yaml"); // Any YAML with sensor type setup correctly + SensorBasePtr sen_b_ptr = setupSensor("USB_CAM", "CAMERA_test", vu_root + path_yaml_file + "/FAST.yaml"); // Any YAML with sensor type setup correctly SensorCameraPtr sen_ptr = std::static_pointer_cast<SensorCamera>(sen_b_ptr); - std::string def_detector = "ORB DET"; + std::string def_detector = "ORB"; std::cout << std::endl << "Which DETECTOR do you want to test? Type one of the registered names [default: " << def_detector << "]: "; std::string det_name = readFromUser(def_detector); DetectorBasePtr det_ptr = setupDetector(det_name, det_name + " detector", vu_root + path_yaml_file + "/" + det_name + ".yaml"); - if (det_name.compare("ORB DET") == 0) + if (det_name.compare("ORB") == 0) det_ptr = std::static_pointer_cast<DetectorORB>(det_ptr); - else if (det_name.compare("FAST DET") == 0) + else if (det_name.compare("FAST") == 0) det_ptr = std::static_pointer_cast<DetectorFAST>(det_ptr); - else if (det_name.compare("SIFT DET") == 0) + else if (det_name.compare("SIFT") == 0) det_ptr = std::static_pointer_cast<DetectorSIFT>(det_ptr); - else if (det_name.compare("SURF DET") == 0) + else if (det_name.compare("SURF") == 0) det_ptr = std::static_pointer_cast<DetectorSURF>(det_ptr); - else if (det_name.compare("BRISK DET") == 0) + else if (det_name.compare("BRISK") == 0) det_ptr = std::static_pointer_cast<DetectorBRISK>(det_ptr); - else if (det_name.compare("MSER DET") == 0) + else if (det_name.compare("MSER") == 0) det_ptr = std::static_pointer_cast<DetectorMSER>(det_ptr); - else if (det_name.compare("GFTT DET") == 0) + else if (det_name.compare("GFTT") == 0) det_ptr = std::static_pointer_cast<DetectorGFTT>(det_ptr); - else if (det_name.compare("HARRIS DET") == 0) + else if (det_name.compare("HARRIS") == 0) det_ptr = std::static_pointer_cast<DetectorHARRIS>(det_ptr); - else if (det_name.compare("SBD DET") == 0) + else if (det_name.compare("SBD") == 0) det_ptr = std::static_pointer_cast<DetectorSBD>(det_ptr); - else if (det_name.compare("KAZE DET") == 0) + else if (det_name.compare("KAZE") == 0) det_ptr = std::static_pointer_cast<DetectorKAZE>(det_ptr); - else if (det_name.compare("AKAZE DET") == 0) + else if (det_name.compare("AKAZE") == 0) det_ptr = std::static_pointer_cast<DetectorAKAZE>(det_ptr); - else if (det_name.compare("AGAST DET") == 0) + else if (det_name.compare("AGAST") == 0) det_ptr = std::static_pointer_cast<DetectorAGAST>(det_ptr); std::cout << "\n================ DESCRIPTOR TEST =================" << std::endl; - std::string def_descriptor = "ORB DES"; + std::string def_descriptor = "ORB"; std::cout << std::endl << "Which DESCRIPTOR do you want to test? Type one of the registered names [default: " << def_descriptor << "]: "; std::string des_name = readFromUser(def_descriptor); DescriptorBasePtr des_ptr = setupDescriptor(des_name, des_name + " descriptor", vu_root + path_yaml_file + "/" + des_name + ".yaml"); - if (des_name.compare("ORB DES") == 0) + if (des_name.compare("ORB") == 0) des_ptr = std::static_pointer_cast<DescriptorORB>(des_ptr); - else if (des_name.compare("SIFT DES") == 0) + else if (des_name.compare("SIFT") == 0) des_ptr = std::static_pointer_cast<DescriptorSIFT>(des_ptr); - else if (des_name.compare("SURF DES") == 0) + else if (des_name.compare("SURF") == 0) des_ptr = std::static_pointer_cast<DescriptorSURF>(des_ptr); - else if (des_name.compare("BRISK DES") == 0) + else if (des_name.compare("BRISK") == 0) des_ptr = std::static_pointer_cast<DescriptorBRISK>(des_ptr); - else if (des_name.compare("KAZE DES") == 0) + else if (des_name.compare("KAZE") == 0) des_ptr = std::static_pointer_cast<DescriptorKAZE>(des_ptr); -// else if (des_name.compare("AKAZE DES") == 0) -// des_ptr = std::static_pointer_cast<DescriptorAKAZE>(des_ptr); -// else if (des_name.compare("LATCH DES") == 0) + else if (des_name.compare("AKAZE") == 0) + des_ptr = std::static_pointer_cast<DescriptorAKAZE>(des_ptr); +// else if (des_name.compare("LATCH") == 0) // des_ptr = std::static_pointer_cast<DescriptorLATCH>(des_ptr); -// else if (des_name.compare("FREAK DES") == 0) +// else if (des_name.compare("FREAK") == 0) // des_ptr = std::static_pointer_cast<DescriptorFREAK>(des_ptr); -// else if (des_name.compare("BRIEF DES") == 0) +// else if (des_name.compare("BRIEF") == 0) // des_ptr = std::static_pointer_cast<DescriptorBRIEF>(des_ptr); -// else if (des_name.compare("DAISY DES") == 0) +// else if (des_name.compare("DAISY") == 0) // des_ptr = std::static_pointer_cast<DescriptorDAISY>(des_ptr); -// else if (des_name.compare("LUCID DES") == 0) +// else if (des_name.compare("LUCID") == 0) // des_ptr = std::static_pointer_cast<DescriptorLUCID>(des_ptr); std::cout << std::endl << "... Testing " << det_ptr->getName() << " with " << des_ptr->getName() << " ..." << std::endl; diff --git a/src/examples/test_detector.cpp b/src/examples/test_detector.cpp index 091f28d6fc564f8143c2c9e65d308fb145f2bf40..517d0ca4e2762bfd918bf7aa419f7bc054756176 100644 --- a/src/examples/test_detector.cpp +++ b/src/examples/test_detector.cpp @@ -35,40 +35,40 @@ int main(void) std::string vu_root = _VU_ROOT_DIR; // Setup camera sensor by default - SensorBasePtr sen_b_ptr = setupSensor("USB CAM", "CAMERA test", vu_root + path_yaml_file + "/FAST.yaml"); // Any YAML with sensor type setup correctly + SensorBasePtr sen_b_ptr = setupSensor("USB_CAM", "CAMERA_test", vu_root + path_yaml_file + "/FAST.yaml"); // Any YAML with sensor type setup correctly SensorCameraPtr sen_ptr = std::static_pointer_cast<SensorCamera>(sen_b_ptr); std::cout << "\n================ DETECTOR TEST =================" << std::endl; - std::string def_detector = "ORB DET"; + std::string def_detector = "ORB"; std::cout << std::endl << "Which DETECTOR do you want to test? Type one of the registered names [default: " << def_detector << "]: "; std::string det_name = readFromUser(def_detector); DetectorBasePtr det_ptr = setupDetector(det_name, det_name + " detector", vu_root + path_yaml_file + "/" + det_name + ".yaml"); - if (det_name.compare("ORB DET") == 0) + if (det_name.compare("ORB") == 0) det_ptr = std::static_pointer_cast<DetectorORB>(det_ptr); - else if (det_name.compare("FAST DET") == 0) + else if (det_name.compare("FAST") == 0) det_ptr = std::static_pointer_cast<DetectorFAST>(det_ptr); - else if (det_name.compare("SIFT DET") == 0) + else if (det_name.compare("SIFT") == 0) det_ptr = std::static_pointer_cast<DetectorSIFT>(det_ptr); - else if (det_name.compare("SURF DET") == 0) + else if (det_name.compare("SURF") == 0) det_ptr = std::static_pointer_cast<DetectorSURF>(det_ptr); - else if (det_name.compare("BRISK DET") == 0) + else if (det_name.compare("BRISK") == 0) det_ptr = std::static_pointer_cast<DetectorBRISK>(det_ptr); - else if (det_name.compare("MSER DET") == 0) + else if (det_name.compare("MSER") == 0) det_ptr = std::static_pointer_cast<DetectorMSER>(det_ptr); - else if (det_name.compare("GFTT DET") == 0) + else if (det_name.compare("GFTT") == 0) det_ptr = std::static_pointer_cast<DetectorGFTT>(det_ptr); - else if (det_name.compare("HARRIS DET") == 0) + else if (det_name.compare("HARRIS") == 0) det_ptr = std::static_pointer_cast<DetectorHARRIS>(det_ptr); - else if (det_name.compare("SBD DET") == 0) + else if (det_name.compare("SBD") == 0) det_ptr = std::static_pointer_cast<DetectorSBD>(det_ptr); - else if (det_name.compare("KAZE DET") == 0) + else if (det_name.compare("KAZE") == 0) det_ptr = std::static_pointer_cast<DetectorKAZE>(det_ptr); - else if (det_name.compare("AKAZE DET") == 0) + else if (det_name.compare("AKAZE") == 0) det_ptr = std::static_pointer_cast<DetectorAKAZE>(det_ptr); - else if (det_name.compare("AGAST DET") == 0) + else if (det_name.compare("AGAST") == 0) det_ptr = std::static_pointer_cast<DetectorAGAST>(det_ptr); std::cout << std::endl << "... Testing " << det_ptr->getName() << " ..." << std::endl; diff --git a/src/examples/test_factories.cpp b/src/examples/test_factories.cpp index 33a30adbc6758a021529b0444d8cf972525036d9..2ad0f781b3e6af79a62f64eb18a01dcd2163785c 100644 --- a/src/examples/test_factories.cpp +++ b/src/examples/test_factories.cpp @@ -22,6 +22,18 @@ int main(void) "There is only one attempt per class, and it is successful!\n" "We do this by registering in the class\'s .cpp file.\n"; + // Root dir path + std::string vu_root = _VU_ROOT_DIR; + + std::string def_sensor = "USB_CAM"; + std::string sen_name = readFromUser(def_sensor); + + std::string file_dot_yaml = "/src/examples/yaml/FAST.yaml"; // Any yaml with sensor configured + + SensorBasePtr sen_b_ptr = setupSensor(sen_name, sen_name + "_test", vu_root + file_dot_yaml); + SensorCameraPtr usb_cam_ptr = std::static_pointer_cast<SensorCamera>(sen_b_ptr); + + return 0; } diff --git a/src/examples/test_sensor.cpp b/src/examples/test_sensor.cpp index f1235efafd9b7e2d9c9e0d6c8c8b4f7ab8a13fa5..e69f5eb53288c54d76a0c99e4e5fa10419431548 100644 --- a/src/examples/test_sensor.cpp +++ b/src/examples/test_sensor.cpp @@ -21,7 +21,7 @@ int main(void) std::cout << std::endl << "Which SENSOR do you want to test? Type one of the registered names [default: " << def_sensor << "]: "; std::string sen_name = readFromUser(def_sensor); - std::string file_dot_yaml = "/src/examples/yaml/example.yaml"; + std::string file_dot_yaml = "/src/examples/yaml/FAST.yaml"; // Any yaml with sensor configured SensorBasePtr sen_b_ptr = setupSensor(sen_name, sen_name + "_test", vu_root + file_dot_yaml); SensorCameraPtr usb_cam_ptr = std::static_pointer_cast<SensorCamera>(sen_b_ptr); diff --git a/src/examples/yaml/AGAST.yaml b/src/examples/yaml/AGAST.yaml index b9cc9fd9d6e62cb48b328e618bfc797295aacab2..17a7b8875cf09afe1be1a2dd9896af8bdb137831 100644 --- a/src/examples/yaml/AGAST.yaml +++ b/src/examples/yaml/AGAST.yaml @@ -1,7 +1,7 @@ sensor: type: "USB_CAM" detector: - type: "AGAST DET" + 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 diff --git a/src/examples/yaml/AKAZE.yaml b/src/examples/yaml/AKAZE.yaml index 4f131ae1fd62bec1e724ce9ad826863c63dc8035..6dcd4edae5c1ab4199df1a44f63ae05060a61c1b 100644 --- a/src/examples/yaml/AKAZE.yaml +++ b/src/examples/yaml/AKAZE.yaml @@ -1,7 +1,18 @@ sensor: type: "USB_CAM" + detector: - type: "AKAZE DET" + type: "AKAZE" + descriptor_type: 5 # Type of the extracted descriptor. DESCRIPTOR_KAZE_UPRIGHT=2, DESCRIPTOR_KAZE=3, DESCRIPTOR_MLDB_UPRIGHT=4, DESCRIPTOR_MLDB=5 + descriptor_size: 0 + descriptor_channels: 3 + threshold: 0.001 + nOctaves: 4 + nOctaveLayers: 4 + diffusivity: 1 # Diffusivity type. DIFF_PM_G1=0, DIFF_PM_G2=1, DIFF_WEICKERT=2, DIFF_CHARBONNIER=3 + +descriptor: + type: "AKAZE" descriptor_type: 5 # Type of the extracted descriptor. DESCRIPTOR_KAZE_UPRIGHT=2, DESCRIPTOR_KAZE=3, DESCRIPTOR_MLDB_UPRIGHT=4, DESCRIPTOR_MLDB=5 descriptor_size: 0 descriptor_channels: 3 diff --git a/src/examples/yaml/BRISK.yaml b/src/examples/yaml/BRISK.yaml index 4bc3254c856894d0a191a5a3b243bf94e0c8e8b5..fa57fe1980b72f814c182f4ac0cb6c9ca64e95dc 100644 --- a/src/examples/yaml/BRISK.yaml +++ b/src/examples/yaml/BRISK.yaml @@ -2,13 +2,13 @@ sensor: type: "USB_CAM" detector: - type: "BRISK DET" + type: "BRISK" thresh: 30 octaves: 3 patternScale: 1.0 descriptor: - type: "BRISK DES" + type: "BRISK" thresh: 30 octaves: 3 patternScale: 1.0 \ No newline at end of file diff --git a/src/examples/yaml/FAST.yaml b/src/examples/yaml/FAST.yaml index f27edcc21ea175fc7045a39d7248ecfed60eba8f..42f8f70ed783cc1fca0b9932fb0cc7fe12e190b1 100644 --- a/src/examples/yaml/FAST.yaml +++ b/src/examples/yaml/FAST.yaml @@ -1,7 +1,7 @@ sensor: type: "USB_CAM" detector: - type: "FAST DET" + type: "FAST" threshold: 10 nonmaxSuppression: true neighbor type: 0 #enum { TYPE_9_16=0, TYPE_7_12=1, TYPE_5_8=2 }; diff --git a/src/examples/yaml/GFTT.yaml b/src/examples/yaml/GFTT.yaml index 71bb32f5e16d8206a5a72cfaf864f0a445889253..239fa22f2f5f046733bd3d4622b4c8255005ac4d 100644 --- a/src/examples/yaml/GFTT.yaml +++ b/src/examples/yaml/GFTT.yaml @@ -1,7 +1,7 @@ sensor: type: "USB_CAM" detector: - type: "GFTT DET" + type: "GFTT" maxCorners: 1000 qualityLevel: 0.01 minDistance: 1.0 diff --git a/src/examples/yaml/HARRIS.yaml b/src/examples/yaml/HARRIS.yaml index 55f83b6396b5baa5b44afc32cba3abc4faf280f1..333ac86192f1a2246661e0b2b162b03c6ad4b367 100644 --- a/src/examples/yaml/HARRIS.yaml +++ b/src/examples/yaml/HARRIS.yaml @@ -1,7 +1,7 @@ sensor: type: "USB_CAM" detector: - type: "HARRIS DET" + type: "HARRIS" maxCorners: 1000 qualityLevel: 0.01 minDistance: 1.0 diff --git a/src/examples/yaml/KAZE.yaml b/src/examples/yaml/KAZE.yaml index 3b4918e1f4e0fa9ecfb316d467902b43316c6ced..d9c0c8cef7dacc0cc3119b452179c073d95c1994 100644 --- a/src/examples/yaml/KAZE.yaml +++ b/src/examples/yaml/KAZE.yaml @@ -2,7 +2,7 @@ sensor: type: "USB_CAM" detector: - type: "KAZE DET" + type: "KAZE" extended: false upright: false threshold: 0.001 @@ -11,7 +11,7 @@ detector: diffusivity: 1 # Diffusivity type. DIFF_PM_G1=0, DIFF_PM_G2=1, DIFF_WEICKERT=2, DIFF_CHARBONNIER=3 descriptor: - type: "KAZE DES" + type: "KAZE" extended: false upright: false threshold: 0.001 diff --git a/src/examples/yaml/MSER.yaml b/src/examples/yaml/MSER.yaml index 0940d88cd46fbe6704a74ae8f1bd857460ade196..6a9ec2f8d949e04c6b2790cafcaec7c2698096f0 100644 --- a/src/examples/yaml/MSER.yaml +++ b/src/examples/yaml/MSER.yaml @@ -1,7 +1,7 @@ sensor: type: "USB_CAM" detector: - type: "MSER DET" + type: "MSER" delta: 5 min_area: 60 max_area: 14400 diff --git a/src/examples/yaml/ORB.yaml b/src/examples/yaml/ORB.yaml index ac01a4690c2250fd12c7a373c4f9c0289555d145..a0246081df96fba0a69b4b03c1ab0acd9326ff48 100644 --- a/src/examples/yaml/ORB.yaml +++ b/src/examples/yaml/ORB.yaml @@ -2,7 +2,7 @@ sensor: type: "USB_CAM" detector: - type: "ORB DET" + type: "ORB" nfeatures: 100 scale factor: 2 nlevels: 8 @@ -13,7 +13,7 @@ detector: patch size: 15 # 31 descriptor: - type: "ORB DES" + type: "ORB" nfeatures: 100 scale factor: 2 nlevels: 8 diff --git a/src/examples/yaml/SBD.yaml b/src/examples/yaml/SBD.yaml index 2c30027994e18bb52de7239e2f9c997b3aa31072..edfd8a5ce5378aa93222cb92ffd743748b7c572c 100644 --- a/src/examples/yaml/SBD.yaml +++ b/src/examples/yaml/SBD.yaml @@ -1,7 +1,7 @@ sensor: type: "USB_CAM" detector: - type: "SBD DET" + type: "SBD" thresholdStep: 10.0 minThreshold: 50.0 maxThreshold: 220.0 diff --git a/src/examples/yaml/SIFT.yaml b/src/examples/yaml/SIFT.yaml index 739742f909e67a186b0cf5d2b083032587a385c2..93404329a5d7367839f7805e066a0dfc3306d166 100644 --- a/src/examples/yaml/SIFT.yaml +++ b/src/examples/yaml/SIFT.yaml @@ -2,7 +2,7 @@ sensor: type: "USB_CAM" detector: - type: "SIFT DET" + type: "SIFT" nfeatures: 0 nOctaveLayers: 3 contrastThreshold: 0.04 @@ -10,7 +10,7 @@ detector: sigma: 1.6 descriptor: - type: "SIFT DES" + type: "SIFT" nfeatures: 0 nOctaveLayers: 3 contrastThreshold: 0.04 diff --git a/src/examples/yaml/SURF.yaml b/src/examples/yaml/SURF.yaml index cb5cbff28ffeea6cba2c0541931e6f8e4ae7c4aa..69c61fec612b89cf3dba84c88f85c2ac9a58b152 100644 --- a/src/examples/yaml/SURF.yaml +++ b/src/examples/yaml/SURF.yaml @@ -2,7 +2,7 @@ sensor: type: "USB_CAM" detector: - type: "SURF DET" + type: "SURF" hessianThreshold: 400 nOctaves: 4 nOctaveLayers: 2 @@ -10,7 +10,7 @@ detector: upright: false descriptor: - type: "SURF DES" + type: "SURF" hessianThreshold: 400 nOctaves: 4 nOctaveLayers: 2 diff --git a/src/sensors/usb_cam/usb_cam.cpp b/src/sensors/usb_cam/usb_cam.cpp index 32116843a507f3638cf13c033b005ac4da9eaca1..235023fcfb202ca717d3ff30fc796e87a62f9a85 100644 --- a/src/sensors/usb_cam/usb_cam.cpp +++ b/src/sensors/usb_cam/usb_cam.cpp @@ -14,5 +14,5 @@ SensorCamera::~SensorCamera(void) #include "../sensor_factory.h" namespace vision_utils { -VU_REGISTER_SENSOR("USB CAM", SensorCamera); +VU_REGISTER_SENSOR("USB_CAM", SensorCamera); } /* namespace vision_utils */ diff --git a/src/sensors/usb_cam/usb_cam_load_yaml.cpp b/src/sensors/usb_cam/usb_cam_load_yaml.cpp index b3fd58f104313be8c957f3c7857fb973c03dddd2..9fa57b2e3d2e7bd50e3a51110cfaaf3572502103 100644 --- a/src/sensors/usb_cam/usb_cam_load_yaml.cpp +++ b/src/sensors/usb_cam/usb_cam_load_yaml.cpp @@ -22,7 +22,7 @@ static ParamsBasePtr createParamsUSBCAMSensor(const std::string & _filename_dot_ if (!yaml_params.IsNull()) { Node d_yaml = yaml_params["sensor"]; - if(d_yaml["type"].as<string>() == "USB CAM") + if(d_yaml["type"].as<string>() == "USB_CAM") { // TODO: Load intrinsic parametes if any function needs them. }else @@ -35,7 +35,7 @@ static ParamsBasePtr createParamsUSBCAMSensor(const std::string & _filename_dot_ } // Register in the SensorFactory -const bool registered_usbcam_params = ParamsFactory::get().registerCreator("USB CAM", createParamsUSBCAMSensor); +const bool registered_usbcam_params = ParamsFactory::get().registerCreator("USB_CAM", createParamsUSBCAMSensor); } /* namespace [unnamed] */