matcher.h
Go to the documentation of this file.
00001 #include <sensor_msgs/CameraInfo.h>
00002 #include <opencv2/opencv.hpp>
00003 #include <pcl/point_cloud.h>
00004 #include <pcl/point_types.h>
00005 #include <image_geometry/pinhole_camera_model.h>
00006 
00007 namespace custom_landmark_2d {
00008 
00010 class Frame {
00011     public:
00013         cv::Point p1;
00015         cv::Point p2;
00017         float score; 
00018 
00019         Frame();
00020         Frame(const cv::Point p1, const cv::Point p2, const float score);
00021 };
00022 
00063 class Matcher {
00064 
00065     public:
00069         int count_times;
00073         float match_limit;
00074 
00078         Matcher();
00079 
00081         void set_template(const cv::Mat& templ);
00082 
00086         void set_cam_model(const sensor_msgs::CameraInfoConstPtr& camera_info);
00087 
00095         bool Match(const cv::Mat& scene, std::vector<Frame>* lst);
00096 
00109         bool Match(const cv::Mat& rgb, const cv::Mat& depth, 
00110                    std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>* object_clouds);
00111 
00125         bool FrameToCloud(const cv::Mat& rgb, const cv::Mat& depth, const Frame& f,
00126                           pcl::PointCloud<pcl::PointXYZRGB>::Ptr object_cloud);
00127 
00128     private:
00129         int match_method_;
00130         int x_dist_, y_dist_;
00131         cv::Mat templ_;
00132         image_geometry::PinholeCameraModel cam_model_;
00133 
00134         // performs a single match on the given scene & scaled_templ
00135         void exact_match(const cv::Mat& scene, const cv::Mat& scaled_templ, std::vector<Frame>* lst);
00136         // checks whether point(x, y) is around any frame in the vector, returns such frame if found
00137         bool around_frame(int x, int y, std::vector<Frame>* lst, Frame** p_ptr_ptr);
00138         // checks whether point(x, y) is around point p using the current x_dist_ & y_dist_
00139         bool around_point(int x, int y, cv::Point& p);
00140         // check that rgb & depth have the required properties like dimensions & encodings
00141         void check_rgbd(const cv::Mat& rgb, const cv::Mat& depth);
00142 };
00143 
00144 }  // namespace custom_landmark_2d


custom_landmark_2d
Author(s):
autogenerated on Thu Jun 6 2019 18:35:43