frame.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2009, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 //
00036 // Visual Odometry classes and functions
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 // PCL headers
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 // Forward declaration.
00075 namespace frame_common
00076 {
00077 
00083   class Frame
00084   {
00085   public:    
00086     int frameId; 
00087 
00088     // image section
00089     bool isStereo;              
00090     cv::Mat img;                
00091     CamParams cam;              
00092     Eigen::Matrix3d iproj;     
00093 
00094     // feature section: keypoints and corresponding descriptors
00095     std::vector<cv::KeyPoint> kpts; 
00096     std::vector<cv::KeyPoint> tkpts; 
00097     cv::Mat dtors;              
00098 
00099     // stereo
00100     cv::Mat imgRight;           
00101     Eigen::Matrix4d disp_to_cart; 
00102     Eigen::Matrix4d cart_to_disp; 
00103     void setCamParams(const CamParams &c); 
00104 
00105     // these are for stereo; do we need monocular ones?
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     // these are for point-to-plane matches
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 // needed for 16B alignment
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       // TODO: Have an initializer with some parameters here.
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 } // end of namespace frame_common
00236 
00238 /*namespace pe
00239 {
00240   struct Match
00241   {
00242     int index1;      //!< The index of the descriptor from the first set.
00243     int index2;      //!< The index of the descriptor from the second set.
00244     float distance;
00245 
00246     Match(int index1, int index2, float distance = 0.0f)
00247       : index1(index1), index2(index2), distance(distance)
00248     {
00249     }
00250   };
00251 } // namespace pe
00252 */
00253 #endif // _FRAME_H_
00254 


frame_common
Author(s): Kurt Konolige
autogenerated on Thu Jan 2 2014 12:12:04