Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 #ifndef ORMatchingModule_H
00010 #define ORMatchingModule_H
00011 
00012 #include <deque>
00013 
00014 #include <ros/ros.h>
00015 #include <or_msgs/OrCommand.h>
00016 #include <or_msgs/ExtractKeyPoints.h>
00017 #include <or_msgs/OrImage.h>
00018 
00019 #include "KeyPointExtraction/KeyPoint.h"
00020 #include "ObjectRecognition/ObjectProperties.h"
00021 #include "ObjectRecognition/MatchResult.h"
00022 #include "KeyPointExtraction/KeyPointMatch.h"
00023 
00024 #include "ObjectRecognition/ImagePropertiesCV.h"
00025 
00026 #include "Workers/Math/Box2D.h"
00027 
00028 class FLANNMatcher;
00029 
00030 class KeyPointExtractor;
00031 
00037 class ORMatchingModule
00038 {
00039   public:
00040 
00042     ORMatchingModule(ros::NodeHandle *nh, std::string inputTopic);
00043 
00045     virtual ~ORMatchingModule();
00046 
00047     void addObjectProperties(ObjectProperties* newProperties);
00048 
00049     void callbackOrCommand( const or_msgs::OrCommand::ConstPtr& msg );
00050     void callbackExtractKeyPoints( const or_msgs::ExtractKeyPoints::ConstPtr& msg );
00051     void callbackImage( const sensor_msgs::Image::ConstPtr& message );
00052 
00053     void processImageMessage( const sensor_msgs::Image::ConstPtr& message );
00054 
00055   private:
00056 
00057     enum Stage1MatcherT
00058     {
00059       NearestNeighbor=1,
00060       Flann=2
00061     };
00062 
00063     enum Stage2MatcherT
00064     {
00065       SimpleHoughClustering=1,
00066       HoughClustering=2
00067     };
00068 
00071     void processImages(  cv::Mat* image, int seqNum, std::vector< Box2D<int> > boundingBoxes=std::vector< Box2D<int> >() );
00072 
00074     void processKeyPoints( cv::Mat* image, std::vector< KeyPoint > *rawKeyPoints, std::vector< Box2D<int> > boundingBoxes, unsigned seqNum );
00075 
00077     bool matchObject( std::vector< KeyPoint >* sceneKeyPoints, ObjectProperties& objectProperties, MatchResult& matchResult );
00078 
00079     
00080     std::list< KeyPointMatch > matchStage1( std::vector< KeyPoint > *sceneKeyPoints, ImagePropertiesCV *objectImageProperties );
00081 
00082     
00083     std::list< KeyPointMatch > matchStage1Flan(ImagePropertiesCV *objectImageProperties );
00084 
00085     
00086     std::vector< std::list< KeyPointMatch> > matchStage2( std::vector< KeyPoint > *sceneKeyPoints, ImagePropertiesCV *objectImageProperties, std::list< KeyPointMatch > &stage1Matches );
00087 
00088     
00089     std::list< KeyPointMatch > matchStage3( std::vector< KeyPoint > *sceneKeyPoints,
00090         ImagePropertiesCV *objImageProperties,
00091         std::vector< std::list< KeyPointMatch> > &stage2Matches,
00092         Homography &homography );
00093 
00094     
00095     std::vector<KeyPoint> getSceneKeyPointsWithinOutline(std::vector< KeyPoint >* sceneKeyPoints, Homography& homography, std::list< KeyPointMatch >& stage3Matches);
00096 
00097     void removeObjectProperties(std::string name);
00098     void sendObjectNames();
00099 
00100     std::deque<ObjectProperties> m_ObjectList;
00101 
00102     int m_ImagesRequested;
00103     std::vector< Box2D<double> > m_BoundingBoxes;
00104 
00105     Stage1MatcherT m_Stage1Matcher;
00106     Stage2MatcherT m_Stage2Matcher;
00107 
00108     int m_ImageWidth;
00109     int m_ImageHeight;
00110 
00111     KeyPointExtractor* m_Extractor;
00112 
00113     std::list<double> m_ProcessingTimes;
00114 
00115     FLANNMatcher* m_FlannMatcher;
00116 
00117     ros::Subscriber m_OrCommandSubscriber;
00118     ros::Subscriber m_ExtractKeyPointsSubscriber;
00119     ros::Subscriber m_ImageSubscriber;
00120 
00121     ros::Publisher m_ORMatchResultPublisher;
00122     ros::Publisher m_ORObjectNamesPublisher;
00123 
00124 };
00125 
00126 
00127 #endif