Go to the documentation of this file.00001
00009 #ifndef UCL_DRONE_KEYFRAME_H
00010 #define UCL_DRONE_KEYFRAME_H
00011 #define PCL_NO_PRECOMPILE
00012
00013 #include <ucl_drone/ucl_drone.h>
00014
00015
00016 #include <opencv2/calib3d/calib3d.hpp>
00017 #include <opencv2/core/core.hpp>
00018 #include <opencv2/imgproc/imgproc.hpp>
00019 #include <opencv2/nonfree/features2d.hpp>
00020 #include <opencv2/nonfree/nonfree.hpp>
00021
00022
00023 #include <pcl/common/common_headers.h>
00024 #include <pcl/point_types.h>
00025 #include <pcl_ros/point_cloud.h>
00026
00027 #include <boost/shared_ptr.hpp>
00028
00029
00030 #include <ucl_drone/PointXYZRGBSIFT.h>
00031 #include <ucl_drone/Pose3D.h>
00032
00040 class KeyFrame
00041 {
00042 private:
00043 static std::vector< KeyFrame* > instances_list;
00044
00045 int ID;
00046 std::vector< int > points;
00047 ucl_drone::Pose3D pose;
00048 cv::FlannBasedMatcher matcher;
00049 cv::Mat descriptors;
00050
00051 public:
00052 pcl::PointCloud< pcl::PointXYZRGBSIFT >::Ptr cloud;
00053
00055 KeyFrame();
00056
00059 KeyFrame(ucl_drone::Pose3D& pose);
00060
00062 ~KeyFrame();
00063
00065 static KeyFrame* getKeyFrame(const int ID);
00066
00068 static void resetList();
00069
00073 void addPoints(pcl::PointCloud< pcl::PointXYZRGBSIFT >::Ptr& pointcloud,
00074 std::vector< int >& map_idx_points);
00075
00078 void addPoints(pcl::PointCloud< pcl::PointXYZRGBSIFT >::Ptr& pointcloud);
00079
00081 int getID();
00082
00084 int size();
00085
00087 ucl_drone::Pose3D getPose();
00088
00091 void getDescriptors(cv::Mat& descriptors);
00092
00094 void convertDescriptors();
00095
00102 void matchWithFrame(Frame& frame, std::vector< std::vector< int > >& idx_matching_points,
00103 std::vector< cv::Point3f >& keyframe_matching_points,
00104 std::vector< cv::Point2f >& frame_matching_points);
00105 };
00106
00107 #endif