Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 #ifndef PE_SIMULATED_H_
00036 #define PE_SIMULATED_H_
00037 
00038 #include <vector>
00039 #include <opencv2/core/core.hpp>
00040 #include <opencv2/features2d/features2d.hpp>
00041 #include <frame_common/frame.h>
00042 
00043 namespace pe
00044 {
00045 void generateData(cv::Mat& intrinsics, cv::Mat& R, cv::Mat& T, std::vector<cv::KeyPoint>& points1,
00046                   std::vector<cv::KeyPoint>& points2, std::vector<int>& indices, std::vector<cv::Point3f>& points);
00047 
00048 void generateProjections(const cv::Mat& intrinsics, const cv::Mat& rvec, const cv::Mat& tvec,
00049                          const std::vector<cv::Point3f>& cloud, std::vector<cv::KeyPoint>& keypoints);
00050 void generatePlanarObject(std::vector<cv::Point3f>& points, cv::Point3f N = cv::Point3f(0.0f, 0.0f, 1.0f), float d = 10.0f);
00051 void generate3DPointCloud(std::vector<cv::Point3f>& points, cv::Point3f pmin = cv::Point3f(-1, -1, 5), cv::Point3f pmax = cv::Point3f(1, 1, 10));
00052 
00053 void addLinkNoise(std::vector<cv::DMatch>& indices, double ratio = 0.05);
00054 
00055 void calcVisible(const cv::Mat& intrinsics, const cv::Mat& R, const cv::Mat& T,
00056         const std::vector<cv::Point3f>& objectPoints, const std::vector<cv::Point2f>& imagePoints, std::vector<bool>& visible);
00057 
00058 void generateCube(std::vector<cv::Point3f>& cloud);
00059 void generateRing(std::vector<cv::Point3f>& cloud, cv::Point3f center = cv::Point3f(0, 0, 0));
00060 
00061 class CameraSimulator
00062 {
00063 public:
00064 
00065 
00066 
00067   virtual void getNextFrame(std::vector<cv::KeyPoint>& imagePoints, std::vector<cv::DMatch>& matches) = 0;
00068 };
00069 
00070 class CircleCameraSimulator : public CameraSimulator
00071 {
00072 public:
00073   CircleCameraSimulator(const cv::Mat& intrinsics, const std::vector<cv::Point3f>& cloud);
00074   ~CircleCameraSimulator() {};
00075 
00076   void getNextFrame(std::vector<cv::KeyPoint>& imagePoints, std::vector<cv::DMatch>& matches);
00077   void calcMatches(const std::vector<int>& newVisible, std::vector<cv::DMatch>& matches);
00078 
00079   virtual void initRT();
00080   virtual void updateRT();
00081 
00082 protected:
00083   cv::Mat intrinsics_;
00084   std::vector<cv::Point3f> cloud_;
00085   std::vector<int> visible_;
00086   cv::Mat rvec_, tvec_;
00087   float radius_;
00088   float angle_;
00089 };
00090 
00091 };
00092 
00093 
00094 #endif