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
00036
00037
00038
00039 #ifndef _FRAME_H_
00040 #define _FRAME_H_
00041
00042 #ifndef EIGEN_USE_NEW_STDVECTOR
00043 #define EIGEN_USE_NEW_STDVECTOR
00044 #endif // EIGEN_USE_NEW_STDVECTOR
00045
00046 #include <stdio.h>
00047 #include <iostream>
00048 #include <Eigen/Core>
00049 #include <Eigen/StdVector>
00050 #include <vector>
00051 #include <boost/shared_ptr.hpp>
00052 #include <boost/make_shared.hpp>
00053 #include <frame_common/stereo.h>
00054 #include <frame_common/camparams.h>
00055
00056
00057 #include <pcl/common/common.h>
00058 #include <pcl/point_types.h>
00059 #include <pcl/point_cloud.h>
00060 #include <pcl/features/normal_3d.h>
00061 #include <pcl/kdtree/kdtree_flann.h>
00062 #include <pcl/filters/passthrough.h>
00063 #include <pcl/filters/voxel_grid.h>
00064 #include <pcl/filters/filter.h>
00065 #include <pcl/filters/extract_indices.h>
00066 #include <pcl/common/transforms.h>
00067 #include <pcl/registration/transforms.h>
00068 #include <pcl/registration/icp.h>
00069 #include <pcl/registration/icp_nl.h>
00070
00071 #include <pcl/io/pcd_io.h>
00072
00073
00074
00075 namespace frame_common
00076 {
00077
00083 class Frame
00084 {
00085 public:
00086 int frameId;
00087
00088
00089 bool isStereo;
00090 cv::Mat img;
00091 CamParams cam;
00092 Eigen::Matrix3d iproj;
00093
00094
00095 std::vector<cv::KeyPoint> kpts;
00096 std::vector<cv::KeyPoint> tkpts;
00097 cv::Mat dtors;
00098
00099
00100 cv::Mat imgRight;
00101 Eigen::Matrix4d disp_to_cart;
00102 Eigen::Matrix4d cart_to_disp;
00103 void setCamParams(const CamParams &c);
00104
00105
00106 Eigen::Vector3d cam2pix(const Eigen::Vector3d &cam_coord) const;
00107 Eigen::Vector3d pix2cam(const Eigen::Vector3d &pix_coord) const;
00108 Eigen::Vector3d pix2cam(const cv::KeyPoint &pix_coord, double disp) const;
00109
00111 void setTKpts(Eigen::Vector4d trans, Eigen::Quaterniond rot);
00112
00114 std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > pts;
00115 std::vector<char> goodPts;
00116 std::vector<double> disps;
00117 std::vector<int> ipts;
00118
00119
00121 pcl::PointCloud<pcl::PointXYZRGBNormal> pointcloud;
00122
00124 pcl::PointCloud<pcl::PointXYZRGB> dense_pointcloud;
00125
00127 std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > pl_kpts;
00129 std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > pl_pts;
00131 std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > pl_normals;
00132 std::vector<int> pl_ipts;
00133
00134 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00135 };
00136
00137
00140 class FrameProc
00141 {
00142 public:
00145 FrameProc(int v = 25);
00146
00148 cv::Ptr<cv::FeatureDetector> detector;
00150 cv::Ptr<cv::DescriptorExtractor> extractor;
00151
00153 void setFrameDetector(const cv::Ptr<cv::FeatureDetector>& detector);
00155 void setFrameDescriptor(const cv::Ptr<cv::DescriptorExtractor>& extractor);
00156
00162 void setMonoFrame(Frame& frame, const cv::Mat &img, const cv::Mat& mask = cv::Mat() );
00163
00170 void setStereoPoints(Frame &frame, int nfrac = 0, bool setPointCloud=false);
00171 int ndisp;
00172 bool doSparse;
00173
00181 void setStereoFrame(Frame &frame, const cv::Mat &img, const cv::Mat &imgr, int nfrac = 0,
00182 bool setPointCloud=false);
00183
00192 void setStereoFrame(Frame &frame, const cv::Mat &img, const cv::Mat &imgr, const cv::Mat &left_mask, int nfrac = 0,
00193 bool setPointCloud=false);
00194
00195 };
00196
00197 class PointcloudProc
00198 {
00199 public:
00200
00201
00204 void setPointcloud(Frame &frame, const pcl::PointCloud<pcl::PointXYZRGB>& input_cloud) const;
00205
00207 void match(const Frame& frame0, const Frame& frame1,
00208 const Eigen::Vector3d& trans, const Eigen::Quaterniond& rot,
00209 std::vector<cv::DMatch>& matches) const;
00210
00211 private:
00214 void reduceCloud(const pcl::PointCloud<pcl::PointXYZRGB>& input,
00215 pcl::PointCloud<pcl::PointXYZRGBNormal>& output) const;
00216
00218 Eigen::Vector3d projectPoint(Eigen::Vector4d& point, CamParams cam) const;
00219
00222 void getMatchingIndices(const pcl::PointCloud<pcl::PointXYZRGBNormal>& input,
00223 const pcl::PointCloud<pcl::PointXYZRGBNormal>& output,
00224 std::vector<int>& input_indices, std::vector<int>& output_indices) const;
00225 };
00226
00231 void drawVOtracks(const cv::Mat &image,
00232 const std::vector<Frame, Eigen::aligned_allocator<Frame> > &frames,
00233 cv::Mat &display);
00234
00235 }
00236
00238
00239
00240
00241
00242
00243
00244
00245
00246
00247
00248
00249
00250
00251
00252
00253 #endif // _FRAME_H_
00254