frame.h
Go to the documentation of this file.
00001 
00006 #ifndef FRAME_H
00007 #define FRAME_H
00008 
00009 #include <ros/ros.h>
00010 #include <image_geometry/stereo_camera_model.h>
00011 #include <tf/transform_datatypes.h>
00012 #include <tf_conversions/tf_eigen.h>
00013 #include <pcl_ros/transforms.h>
00014 
00015 #include <opencv2/opencv.hpp>
00016 #include <opencv2/features2d/features2d.hpp>
00017 #include <opencv2/nonfree/features2d.hpp>
00018 #include <opencv2/nonfree/nonfree.hpp>
00019 
00020 #include <pcl/point_types.h>
00021 
00022 using namespace std;
00023 using namespace pcl;
00024 
00025 typedef PointXYZ                     PointXYZ;
00026 typedef PointXYZRGB                  PointRGB;
00027 typedef PointCloud<PointXYZ>         PointCloudXYZ;
00028 typedef PointCloud<PointRGB>         PointCloudRGB;
00029 
00030 namespace slam
00031 {
00032 
00033 class Frame
00034 {
00035 
00036 public:
00037 
00040   Frame();
00041 
00044   Frame(cv::Mat l_img, cv::Mat r_img, image_geometry::StereoCameraModel camera_model, double timestamp);
00045 
00048   inline cv::Mat getLeftImg() const {return l_img_;}
00049 
00052   inline cv::Mat getRightImg() const {return r_img_;}
00053 
00056   inline vector<cv::KeyPoint> getLeftKp() const {return l_kp_;}
00057 
00061   inline void setLeftKp(const vector<cv::KeyPoint>& l_kp){l_kp_ = l_kp;}
00062 
00065   inline vector<cv::KeyPoint> getRightKp() const {return r_kp_;}
00066 
00069   inline cv::Mat getLeftDesc() const {return l_desc_;}
00070 
00074   inline void setLeftDesc(const cv::Mat& l_desc){l_desc_ = l_desc;}
00075 
00078   inline vector<cv::Point3f> getCameraPoints() const {return camera_points_;}
00079 
00083   inline void setId(const int& id){id_ = id;}
00084 
00088   inline void setCameraPoints(const vector<cv::Point3f>& points_3d){camera_points_ = points_3d;}
00089 
00093   inline void setCameraPose(const tf::Transform& camera_pose){camera_pose_ = camera_pose;}
00094 
00098   inline void setPointCloud(const PointCloudRGB::Ptr pointcloud){pointcloud_ = pointcloud;}
00099 
00103   inline void setInliersNumWithPreviousFrame(const int& num_inliers){num_inliers_with_prev_frame_ = num_inliers;}
00104 
00107   inline int getId() const {return id_;}
00108 
00111   inline tf::Transform getCameraPose() const {return camera_pose_;}
00112 
00115   inline vector< vector<int> > getClusters() const {return clusters_;}
00116 
00119   inline vector<Eigen::Vector4f> getClusterCentroids() const {return cluster_centroids_;}
00120 
00123   inline double getTimestamp() const {return stamp_;}
00124 
00127   inline PointCloudRGB::Ptr getPointCloud() const {return pointcloud_;}
00128 
00131   inline int getInliersNumWithPreviousFrame() const {return num_inliers_with_prev_frame_;}
00132 
00136   cv::Mat computeSift();
00137 
00140   void regionClustering();
00141 
00142 protected:
00143 
00150   vector<int> regionQuery(vector<cv::KeyPoint> *keypoints, cv::KeyPoint *keypoint, float eps);
00151 
00152 private:
00153 
00154   int id_; 
00155 
00156   cv::Mat l_img_; 
00157   cv::Mat r_img_; 
00158 
00159   vector<cv::KeyPoint> l_kp_; 
00160   vector<cv::KeyPoint> r_kp_; 
00161 
00162   cv::Mat l_desc_; 
00163   cv::Mat r_desc_; 
00164 
00165   vector<cv::Point3f> camera_points_; 
00166 
00167   vector< vector<int> > clusters_; 
00168 
00169   vector<Eigen::Vector4f> cluster_centroids_; 
00170 
00171   tf::Transform camera_pose_; 
00172 
00173   double stamp_; 
00174 
00175   PointCloudRGB::Ptr pointcloud_; 
00176 
00177   ros::Publisher kp_pub_; 
00178 
00179   int num_inliers_with_prev_frame_; 
00180 
00181 };
00182 
00183 } // namespace
00184 
00185 #endif // FRAME_H


stereo_slam
Author(s): Pep Lluis Negre
autogenerated on Thu Jun 6 2019 21:40:57