feature_detector.cpp
Go to the documentation of this file.
00001 
00024 #include "ccny_rgbd/features/feature_detector.h"
00025 
00026 namespace ccny_rgbd {
00027 
00028 FeatureDetector::FeatureDetector():
00029   compute_descriptors_(false)
00030 {
00031 
00032 }
00033 
00034 FeatureDetector::~FeatureDetector()
00035 {
00036 
00037 }
00038 
00039 void FeatureDetector::findFeatures(RGBDFrame& frame)
00040 {
00041   boost::mutex::scoped_lock(mutex_);
00042   
00043   const cv::Mat& input_img = frame.rgb_img;
00044 
00045   // convert from RGB to grayscale
00046   cv::Mat gray_img(input_img.rows, input_img.cols, CV_8UC1);
00047   cvtColor(input_img, gray_img, CV_BGR2GRAY);
00048 
00049   // blur if needed
00050   if(smooth_ > 0)
00051   {
00052     int blur_size = smooth_*2 + 1;
00053     cv::GaussianBlur(gray_img, gray_img, cv::Size(blur_size, blur_size), 0);
00054   }
00055 
00056   // find the 2D coordinates of keypoints
00057   findFeatures(frame, gray_img);
00058 
00059   // calculates the 3D position and covariance of features
00060   frame.computeDistributions(max_range_, max_stdev_);
00061 }
00062 
00063 void FeatureDetector::setSmooth(int smooth)
00064 {
00065   smooth_ = smooth;
00066 }
00067 
00068 void FeatureDetector::setMaxRange(double max_range)
00069 {
00070   max_range_ = max_range;
00071 }
00072 
00073 void FeatureDetector::setMaxStDev(double max_stdev)
00074 {
00075   max_stdev_ = max_stdev;
00076 }
00077 
00078 int FeatureDetector::getSmooth() const
00079 {
00080   return smooth_;
00081 }
00082 
00083 double FeatureDetector::getMaxRange() const
00084 {
00085   return max_range_;
00086 } 
00087 
00088 double FeatureDetector::getMaxStDev() const
00089 {
00090   return max_stdev_;
00091 } 
00092 
00093 } // namespace ccny_rgbd
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


ccny_rgbd
Author(s): Ivan Dryanovski
autogenerated on Fri Apr 12 2013 20:38:48