Go to the documentation of this file.00001
00010 #ifndef _RECOGNIZER_3D_
00011 #define _RECOGNIZER_3D_
00012
00013 #include <blort/Recognizer3D/DetectGPUSIFT.hh>
00014 #include <blort/Recognizer3D/ODetect3D.hh>
00015 #include <blort/Recognizer3D/Object3D.hh>
00016 #include <blort/Recognizer3D/ModelObject3D.hh>
00017 #include <blort/Recognizer3D/KeypointDescriptor.hh>
00018 #include <blort/Recognizer3D/PoseCv.hh>
00019 #include <blort/TomGine/tgModel.h>
00020 #include <blort/TomGine/tgPose.h>
00021 #include <string>
00022 #include <opencv2/core/core.hpp>
00023 #include <sensor_msgs/CameraInfo.h>
00024
00025 namespace blortRecognizer{
00026
00030 struct CameraParameter {
00031 int w,h;
00032 float fx, fy;
00033 float cx, cy;
00034 float k1, k2, k3;
00035 float p1, p2;
00036 CameraParameter(){ w=h=fx=fy=cx=cy=k1=k2=k3=p1=p2=0; }
00037 CameraParameter(const sensor_msgs::CameraInfo& cam_info);
00038 };
00039
00040 struct Siftex{
00041 vec3 pos;
00042 vec3 normal;
00043 vec3 viewray;
00044 };
00045
00047 class Recognizer3D{
00048
00049 public:
00054 Recognizer3D(const CameraParameter& camParam, std::string config_root = "",
00055 bool display = false, bool training = false);
00056
00057 ~Recognizer3D();
00058
00059 void setCameraParameter(const blortRecognizer::CameraParameter& camParam);
00060
00061 void setGaussian(int kernel, float stdDeviation){ m_gauss_kernel = kernel; m_gauss_dev = stdDeviation; }
00062
00068 bool recognize(IplImage* tFrame, std::map<std::string, boost::shared_ptr<TomGine::tgPose> > & poses, std::map<std::string, double> & confs);
00069
00076 bool recognize(IplImage* tFrame, std::map<std::string, boost::shared_ptr<TomGine::tgPose> > & poses, std::map<std::string, double> & confs, const std::map<std::string, bool> & select);
00077
00079 void initTrainingModel();
00080
00081
00086 bool learnSifts(IplImage* tFrame, const TomGine::tgModel& model, const TomGine::tgPose& pose);
00087
00091 bool loadModelFromFile(const std::string sift_file);
00092
00096 bool saveModelToFile(const char* sift_file);
00097
00101 void getSifts(std::vector<Siftex>& sl){ sl = m_siftexlist; }
00102
00106 void getLastSifts(std::vector<Siftex> &sl){ sl = m_lastsiftexlist; }
00107
00108
00109 cv::Mat getImage(){ return display_image; }
00110 void setDoUndistort(bool enable){ do_undistort = enable; }
00111
00112 static void Convert(P::PoseCv& p1, TomGine::tgPose& p2);
00113
00114 void setNNThreshold(double nn_threshold);
00115 void setRansacNPointsToMatch(unsigned int n);
00116 cv::Mat getDebugImage(){ return debug_image; }
00117
00118 private:
00119 Recognizer3D();
00120
00121 P::DetectGPUSIFT sift;
00122
00123 P::ModelObject3D m_sift_model_learner;
00124
00125 P::ODetect3D m_detect;
00126
00127 std::vector< boost::shared_ptr<P::Object3D> > m_sift_models;
00128
00129
00130 P::Array<P::KeypointDescriptor*> m_image_keys;
00131
00132 std::vector<Siftex> m_lastsiftexlist;
00133 std::vector<Siftex> m_siftexlist;
00134
00135 CvMat *pIntrinsicDistort;
00136 CvMat *pDistortion;
00137 CvMat *C;
00138 CvMat *pMapX, *pMapY;
00139 CameraParameter m_cp;
00140
00141 bool m_model_loaded;
00142 bool m_display;
00143
00144 int m_gauss_kernel;
00145 float m_gauss_dev;
00146
00147
00148 cv::Mat display_image;
00149 cv::Mat debug_image;
00150 bool do_undistort;
00151 std::string config_root;
00152
00153 };
00154
00155 }
00156
00157 #endif