diff --git a/src/processor_image_feature.cpp b/src/processor_image_feature.cpp index e7387ccdcf9b5d205f9b2830128908d71d4c77e0..0c6155214f2fd4922452da5932d4851207385582 100644 --- a/src/processor_image_feature.cpp +++ b/src/processor_image_feature.cpp @@ -10,6 +10,58 @@ namespace wolf { +#if defined (HAVE_OPENCV3) + +ProcessorImageFeature::ProcessorImageFeature(ProcessorParamsImage _params) : + ProcessorTrackerFeature("IMAGE", _params.algorithm.max_new_features), + params_(_params), + active_search_grid_() +{ + // 1. detector-descriptor params + DetectorDescriptorParamsBasePtr _dd_params = _params.detector_descriptor_params_ptr; + switch (_dd_params->type){ + case DD_BRISK: + { + std::shared_ptr<DetectorDescriptorParamsBrisk> params_brisk = std::static_pointer_cast<DetectorDescriptorParamsBrisk>(_dd_params); + + detector_descriptor_ptr_ = cv::BRISK::create(params_brisk->threshold, // + params_brisk->octaves, // + params_brisk->pattern_scale); + + detector_descriptor_params_.pattern_radius_ = std::max((unsigned int)((params_brisk->nominal_pattern_radius)*pow(2,params_brisk->octaves)), + (unsigned int)((params_brisk->nominal_pattern_radius)*params_brisk->pattern_scale)); + detector_descriptor_params_.size_bits_ = detector_descriptor_ptr_->descriptorSize() * 8; + + break; + } + case DD_ORB: + { + std::shared_ptr<DetectorDescriptorParamsOrb> params_orb = std::static_pointer_cast<DetectorDescriptorParamsOrb>(_dd_params); + detector_descriptor_ptr_ = cv::ORB::create(params_orb->nfeatures, // + params_orb->scaleFactor, // + params_orb->nlevels, // + params_orb->edgeThreshold, // + params_orb->firstLevel, // + params_orb->WTA_K, // + params_orb->scoreType, // + params_orb->patchSize); + + detector_descriptor_params_.pattern_radius_ = params_orb->edgeThreshold; + detector_descriptor_params_.size_bits_ = detector_descriptor_ptr_->descriptorSize() * 8; + + break; + } + default: + throw std::runtime_error("Unknown detector-descriptor type"); + } + + // 2. matcher params +// TODO: FIX this + matcher_ptr_ = cv::DescriptorMatcher::create("BruteForce"); +// matcher_ptr_ = cv::DescriptorMatcher::create(_params.matcher.similarity_norm); +} +#else + ProcessorImageFeature::ProcessorImageFeature(ProcessorParamsImage _params) : ProcessorTrackerFeature("IMAGE", _params.algorithm.max_new_features), matcher_ptr_(nullptr), @@ -59,6 +111,8 @@ ProcessorImageFeature::ProcessorImageFeature(ProcessorParamsImage _params) : } +#endif + //Destructor ProcessorImageFeature::~ProcessorImageFeature() { diff --git a/src/processor_image_feature.h b/src/processor_image_feature.h index 69f1444f365aa0f9cab8a015bec044c1b290b0ff..de47e205853131a9037890754b06aa1ee35170b5 100644 --- a/src/processor_image_feature.h +++ b/src/processor_image_feature.h @@ -13,30 +13,36 @@ // OpenCV includes #if defined (HAVE_OPENCV3) - #include <opencv2/features2d.hpp> - #include <opencv2/highgui.hpp> - #include <opencv2/core.hpp> - #include <opencv2/imgproc.hpp> +#include <opencv2/features2d.hpp> +#include <opencv2/highgui.hpp> +#include <opencv2/core.hpp> +#include <opencv2/imgproc.hpp> #else - #include <opencv2/features2d/features2d.hpp> - #include <opencv2/highgui/highgui.hpp> - #include <opencv2/core/core.hpp> +#include <opencv2/features2d/features2d.hpp> +#include <opencv2/highgui/highgui.hpp> +#include <opencv2/core/core.hpp> #endif // General includes #include <cmath> #include <complex> // std::complex, std::norm -namespace wolf { - +namespace wolf +{ + WOLF_PTR_TYPEDEFS(ProcessorImageFeature); - + //class class ProcessorImageFeature : public ProcessorTrackerFeature { protected: +#if defined (HAVE_OPENCV3) + cv::Ptr<cv::DescriptorMatcher> matcher_ptr_; + cv::Ptr<cv::FeatureDetector> detector_descriptor_ptr_; +#else std::shared_ptr<cv::DescriptorMatcher> matcher_ptr_; std::shared_ptr<cv::Feature2D> detector_descriptor_ptr_; +#endif protected: ProcessorParamsImage params_; // Struct with parameters of the processors @@ -46,12 +52,12 @@ class ProcessorImageFeature : public ProcessorTrackerFeature { unsigned int pattern_radius_; ///< radius of the pattern used to detect a key-point at pattern_scale = 1.0 and octaves = 0 unsigned int size_bits_; ///< length of the descriptor vector in bits - }detector_descriptor_params_; + } detector_descriptor_params_; struct { unsigned int width_; ///< width of the image unsigned int height_; ///< height of the image - }image_; + } image_; // Lists to store values to debug std::list<cv::Rect> tracker_roi_; @@ -101,7 +107,8 @@ class ProcessorImageFeature : public ProcessorTrackerFeature * \param _incoming_feature input/output feature in incoming capture to be corrected * \return false if the the process discards the correspondence with origin's feature */ - virtual bool correctFeatureDrift(const FeatureBasePtr _origin_feature, const FeatureBasePtr _last_feature, FeatureBasePtr _incoming_feature); + virtual bool correctFeatureDrift(const FeatureBasePtr _origin_feature, const FeatureBasePtr _last_feature, + FeatureBasePtr _incoming_feature); /** \brief Vote for KeyFrame generation * @@ -135,7 +142,7 @@ class ProcessorImageFeature : public ProcessorTrackerFeature * \return the number of detected features */ virtual unsigned int detect(cv::Mat _image, cv::Rect& _roi, std::vector<cv::KeyPoint>& _new_keypoints, - cv::Mat& new_descriptors); + cv::Mat& new_descriptors); private: /** @@ -165,8 +172,8 @@ class ProcessorImageFeature : public ProcessorTrackerFeature * \param _cv_matches output variable in which the best result will be stored (in the position [0]) * \return normalized score of similarity (1 - exact match; 0 - complete mismatch) */ - virtual Scalar match(cv::Mat _target_descriptor, cv::Mat _candidate_descriptors, std::vector<cv::DMatch>& _cv_matches); - + virtual Scalar match(cv::Mat _target_descriptor, cv::Mat _candidate_descriptors, + std::vector<cv::DMatch>& _cv_matches); // These only to debug, will disappear one day public: @@ -176,8 +183,8 @@ class ProcessorImageFeature : public ProcessorTrackerFeature virtual void resetVisualizationFlag(FeatureBaseList& _feature_list_last); public: - static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr sensor_ptr = nullptr); - + static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, + const SensorBasePtr sensor_ptr = nullptr); }; @@ -186,9 +193,11 @@ inline bool ProcessorImageFeature::voteForKeyFrame() return (incoming_ptr_->getFeatureList().size() < params_.algorithm.min_features_for_keyframe); } -inline ConstraintBasePtr ProcessorImageFeature::createConstraint(FeatureBasePtr _feature_ptr, FeatureBasePtr _feature_other_ptr) +inline ConstraintBasePtr ProcessorImageFeature::createConstraint(FeatureBasePtr _feature_ptr, + FeatureBasePtr _feature_other_ptr) { - ConstraintEpipolarPtr const_epipolar_ptr = std::make_shared<ConstraintEpipolar>(_feature_ptr, _feature_other_ptr, shared_from_this()); + ConstraintEpipolarPtr const_epipolar_ptr = std::make_shared < ConstraintEpipolar + > (_feature_ptr, _feature_other_ptr, shared_from_this()); // _feature_ptr->addConstraint(const_epipolar_ptr); // _feature_other_ptr->addConstrainedBy(const_epipolar_ptr); return const_epipolar_ptr; @@ -196,5 +205,4 @@ inline ConstraintBasePtr ProcessorImageFeature::createConstraint(FeatureBasePtr } // namespace wolf - #endif // PROCESSOR_IMAGE_FEATURE_H diff --git a/src/processor_image_landmark.cpp b/src/processor_image_landmark.cpp index ff9136c351250ba4e6ef72957adb9f5d82adc045..7e45c81880352e6cbbfa670eae97132abb348ffc 100644 --- a/src/processor_image_landmark.cpp +++ b/src/processor_image_landmark.cpp @@ -14,6 +14,60 @@ namespace wolf { +#if defined (HAVE_OPENCV3) + +ProcessorImageLandmark::ProcessorImageLandmark(const ProcessorParamsImage& _params) : + ProcessorTrackerLandmark("IMAGE LANDMARK", _params.algorithm.max_new_features, _params.algorithm.time_tolerance), + params_(_params), + active_search_grid_(), + n_feature_(0), + landmark_idx_non_visible_(0) +{ + // 1. detector-descriptor params + std::shared_ptr<DetectorDescriptorParamsBase> _dd_params = _params.detector_descriptor_params_ptr; + switch (_dd_params->type){ + case DD_BRISK: + { + std::shared_ptr<DetectorDescriptorParamsBrisk> params_brisk = std::static_pointer_cast<DetectorDescriptorParamsBrisk>(_dd_params); + detector_descriptor_ptr_ = cv::BRISK::create(params_brisk->threshold, // + params_brisk->octaves, // + params_brisk->pattern_scale); + + detector_descriptor_params_.pattern_radius_ = std::max((unsigned int)((params_brisk->nominal_pattern_radius)*pow(2,params_brisk->octaves)), + (unsigned int)((params_brisk->nominal_pattern_radius)*params_brisk->pattern_scale)); + + detector_descriptor_params_.size_bits_ = detector_descriptor_ptr_->descriptorSize() * 8; + + break; + } + case DD_ORB: + { + std::shared_ptr<DetectorDescriptorParamsOrb> params_orb = std::static_pointer_cast<DetectorDescriptorParamsOrb>(_dd_params); + detector_descriptor_ptr_ = cv::ORB::create(params_orb->nfeatures, // + params_orb->scaleFactor, // + params_orb->nlevels, // + params_orb->edgeThreshold, // + params_orb->firstLevel, // + params_orb->WTA_K, // + params_orb->scoreType, // + params_orb->patchSize); + + detector_descriptor_params_.pattern_radius_ = params_orb->edgeThreshold; + detector_descriptor_params_.size_bits_ = detector_descriptor_ptr_->descriptorSize() * 8; + + break; + } + default: + throw std::runtime_error("Unknown detector-descriptor type"); + } + + // 2. matcher params + // TODO: FIX this + matcher_ptr_ = cv::DescriptorMatcher::create("BruteForce"); + // matcher_ptr_ = cv::DescriptorMatcher::create(_params.matcher.similarity_norm); +} + +#else ProcessorImageLandmark::ProcessorImageLandmark(const ProcessorParamsImage& _params) : ProcessorTrackerLandmark("IMAGE LANDMARK", _params.algorithm.max_new_features, _params.algorithm.time_tolerance), @@ -67,6 +121,8 @@ ProcessorImageLandmark::ProcessorImageLandmark(const ProcessorParamsImage& _para } +#endif + ProcessorImageLandmark::~ProcessorImageLandmark() { // diff --git a/src/processor_image_landmark.h b/src/processor_image_landmark.h index 91c1e88516112d43bc0df3cfce21e9e6eee8c1e7..a3732ba631b1b1ec3b28bbacf5fe324395c52832 100644 --- a/src/processor_image_landmark.h +++ b/src/processor_image_landmark.h @@ -39,8 +39,15 @@ WOLF_PTR_TYPEDEFS(ProcessorImageLandmark); class ProcessorImageLandmark : public ProcessorTrackerLandmark { protected: + +#if defined (HAVE_OPENCV3) + cv::Ptr<cv::DescriptorMatcher> matcher_ptr_; + cv::Ptr<cv::FeatureDetector> detector_descriptor_ptr_; +#else std::shared_ptr<cv::DescriptorMatcher> matcher_ptr_; std::shared_ptr<cv::Feature2D> detector_descriptor_ptr_; +#endif + protected: ProcessorParamsImage params_; // Struct with parameters of the processors ActiveSearchGrid active_search_grid_; // Active Search diff --git a/src/test/gtest_roi_ORB.cpp b/src/test/gtest_roi_ORB.cpp index aaa568d1161cd32b39686bf78094a252ae424b2e..ea4d4098ad94afdb8c51899d0d291001321668b0 100644 --- a/src/test/gtest_roi_ORB.cpp +++ b/src/test/gtest_roi_ORB.cpp @@ -12,9 +12,16 @@ #include "logging.h" //opencv includes -#include "opencv2/features2d/features2d.hpp" +#if defined (HAVE_OPENCV3) +#include <opencv2/features2d.hpp> +#include <opencv2/highgui.hpp> +#include <opencv2/core.hpp> +#include <opencv2/imgproc.hpp> +#else +#include <opencv2/features2d/features2d.hpp> #include <opencv2/highgui/highgui.hpp> #include <opencv2/core/core.hpp> +#endif // std include #include <vector> @@ -117,14 +124,25 @@ TEST(RoiORB, RoiBounds) unsigned int scoreType = 0; //#enum { kBytes = 32, HARRIS_SCORE=0, FAST_SCORE=1 }; unsigned int patchSize = 31; - cv::ORB detector(nfeatures, // - scaleFactor, // - nlevels, // - edgeThreshold, // - firstLevel, // - WTA_K, // - scoreType, // - patchSize); +#if defined (HAVE_OPENCV3) + cv::Ptr<cv::FeatureDetector> detector = cv::ORB::create(nfeatures, // + scaleFactor, // + nlevels, // + edgeThreshold, // + firstLevel, // + WTA_K, // + scoreType, // + patchSize); +#else + std::shared_ptr<cv::ORB> detector = std::make_shared<cv::ORB>(nfeatures, // + scaleFactor, // + nlevels, // + edgeThreshold, // + firstLevel, // + WTA_K, // + scoreType, // + patchSize); +#endif std::vector<cv::KeyPoint> target_keypoints; cv::KeyPointsFilter keypoint_filter; @@ -177,7 +195,7 @@ TEST(RoiORB, RoiBounds) cv::Mat image_roi = image(roi_inflated); target_keypoints.clear(); - detector.detect(image_roi, target_keypoints); + detector->detect(image_roi, target_keypoints); if (!target_keypoints.empty()) {