cluster.h
Go to the documentation of this file.
00001 
00006 #ifndef CLUSTER_H
00007 #define CLUSTER_H
00008 
00009 #include <ros/ros.h>
00010 #include <tf/transform_datatypes.h>
00011 
00012 #include <opencv2/opencv.hpp>
00013 #include <opencv2/features2d/features2d.hpp>
00014 
00015 using namespace std;
00016 
00017 namespace slam
00018 {
00019 
00020 class Cluster
00021 {
00022 
00023 public:
00024 
00027   Cluster();
00028 
00031   Cluster(int id, int frame_id, tf::Transform camera_pose, vector<cv::KeyPoint> kp_l, vector<cv::KeyPoint> kp_r, cv::Mat orb_desc, cv::Mat sift_desc, vector<cv::Point3f> points);
00032 
00036   vector<cv::Point3f> getWorldPoints();
00037 
00040   inline int getId() const {return id_;}
00041 
00044   inline int getFrameId() const {return frame_id_;}
00045 
00048   inline vector<cv::KeyPoint> getLeftKp() const {return kp_l_;}
00049 
00052   inline vector<cv::KeyPoint> getRightKp() const {return kp_r_;}
00053 
00056   inline cv::Mat getOrb() const {return orb_desc_;}
00057 
00060   inline cv::Mat getSift() const {return sift_desc_;}
00061 
00064   inline vector<cv::Point3f> getPoints() const {return points_;}
00065 
00068   inline tf::Transform getCameraPose() const {return camera_pose_;}
00069 
00070 private:
00071 
00072 
00073   int id_; 
00074 
00075   int frame_id_; 
00076 
00077   tf::Transform camera_pose_; 
00078 
00079   vector<cv::KeyPoint> kp_l_; 
00080 
00081   vector<cv::KeyPoint> kp_r_; 
00082 
00083   cv::Mat orb_desc_; 
00084   cv::Mat sift_desc_; 
00085 
00086   vector<cv::Point3f> points_; 
00087 
00088 };
00089 
00090 } // namespace
00091 
00092 #endif // CLUSTER_H


stereo_slam
Author(s): Pep Lluis Negre
autogenerated on Thu Jul 14 2016 04:09:13