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 <frame_common/stereo.h>
00053 #include <frame_common/camparams.h>
00054
00055
00056 #include <pcl/common/common.h>
00057 #include <pcl/point_types.h>
00058 #include <pcl/point_cloud.h>
00059 #include <pcl/features/normal_3d.h>
00060 #include <pcl/kdtree/kdtree_flann.h>
00061 #include <pcl/filters/passthrough.h>
00062 #include <pcl/filters/voxel_grid.h>
00063 #include <pcl/filters/filter.h>
00064 #include <pcl/filters/extract_indices.h>
00065 #include <pcl/common/transform.h>
00066 #include <pcl/registration/transforms.h>
00067 #include <pcl/registration/icp.h>
00068 #include <pcl/registration/icp_nl.h>
00069
00070 #include <pcl/io/pcd_io.h>
00071
00072
00073
00074 namespace frame_common
00075 {
00076
00082 class Frame
00083 {
00084 public:
00085 int frameId;
00086
00087
00088 bool isStereo;
00089 cv::Mat img;
00090 CamParams cam;
00091 Eigen::Matrix3d iproj;
00092
00093
00094 std::vector<cv::KeyPoint> kpts;
00095 std::vector<cv::KeyPoint> tkpts;
00096 cv::Mat dtors;
00097
00098
00099 cv::Mat imgRight;
00100 Eigen::Matrix4d disp_to_cart;
00101 Eigen::Matrix4d cart_to_disp;
00102 void setCamParams(const CamParams &c);
00103
00104
00105 Eigen::Vector3d cam2pix(const Eigen::Vector3d &cam_coord) const;
00106 Eigen::Vector3d pix2cam(const Eigen::Vector3d &pix_coord) const;
00107 Eigen::Vector3d pix2cam(const cv::KeyPoint &pix_coord, double disp) const;
00108
00110 void setTKpts(Eigen::Vector4d trans, Eigen::Quaterniond rot);
00111
00113 std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > pts;
00114 std::vector<char> goodPts;
00115 std::vector<double> disps;
00116 std::vector<int> ipts;
00117
00118
00120 pcl::PointCloud<pcl::PointXYZRGBNormal> pointcloud;
00121
00123 pcl::PointCloud<pcl::PointXYZRGB> dense_pointcloud;
00124
00126 std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > pl_kpts;
00128 std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > pl_pts;
00130 std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > pl_normals;
00131 std::vector<int> pl_ipts;
00132
00133 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00134 };
00135
00136
00139 class FrameProc
00140 {
00141 public:
00144 FrameProc(int v = 25);
00145
00147 cv::Ptr<cv::FeatureDetector> detector;
00149 cv::Ptr<cv::DescriptorExtractor> extractor;
00150
00152 void setFrameDetector(const cv::Ptr<cv::FeatureDetector>& detector);
00154 void setFrameDescriptor(const cv::Ptr<cv::DescriptorExtractor>& extractor);
00155
00161 void setMonoFrame(Frame& frame, const cv::Mat &img, const cv::Mat& mask = cv::Mat() );
00162
00169 void setStereoPoints(Frame &frame, int nfrac = 0, bool setPointCloud=false);
00170 int ndisp;
00171 bool doSparse;
00172
00180 void setStereoFrame(Frame &frame, const cv::Mat &img, const cv::Mat &imgr, int nfrac = 0,
00181 bool setPointCloud=false);
00182
00191 void setStereoFrame(Frame &frame, const cv::Mat &img, const cv::Mat &imgr, const cv::Mat &left_mask, int nfrac = 0,
00192 bool setPointCloud=false);
00193
00194 };
00195
00196 class PointcloudProc
00197 {
00198 public:
00199
00200
00203 void setPointcloud(Frame &frame, const pcl::PointCloud<pcl::PointXYZRGB>& input_cloud) const;
00204
00206 void match(const Frame& frame0, const Frame& frame1,
00207 const Eigen::Vector3d& trans, const Eigen::Quaterniond& rot,
00208 std::vector<cv::DMatch>& matches) const;
00209
00210 private:
00213 void reduceCloud(const pcl::PointCloud<pcl::PointXYZRGB>& input,
00214 pcl::PointCloud<pcl::PointXYZRGBNormal>& output) const;
00215
00217 Eigen::Vector3d projectPoint(Eigen::Vector4d& point, CamParams cam) const;
00218
00221 void getMatchingIndices(const pcl::PointCloud<pcl::PointXYZRGBNormal>& input,
00222 const pcl::PointCloud<pcl::PointXYZRGBNormal>& output,
00223 std::vector<int>& input_indices, std::vector<int>& output_indices) const;
00224 };
00225
00230 void drawVOtracks(const cv::Mat &image,
00231 const std::vector<Frame, Eigen::aligned_allocator<Frame> > &frames,
00232 cv::Mat &display);
00233
00234 }
00235
00237
00238
00239
00240
00241
00242
00243
00244
00245
00246
00247
00248
00249
00250
00251
00252 #endif // _FRAME_H_
00253