ndt_frame.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, AASS Research Center, Orebro University.
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 AASS Research Center 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 #ifndef NDTFRAME_HH
00036 #define NDTFRAME_HH
00037 
00038 #include "pcl/point_cloud.h"
00039 #include "pcl/point_types.h"
00040 #include "pcl/io/pcd_io.h"
00041 #include "pcl/features/feature.h"
00042 #include "pcl/registration/icp.h"
00043 #include "pcl/filters/voxel_grid.h"
00044 #include "opencv2/core/core.hpp"
00045 
00046 #include <ndt_map/cell_vector.h>
00047 #include <ndt_map/ndt_map.h>
00048 #include <ndt_map/depth_camera.h>
00049 
00050 #include <ndt_feature_reg/ndt_frame_tools.h>
00051 #include <ndt_map/pointcloud_utils.h>
00052 
00053 namespace ndt_feature_reg
00054 {
00055 inline
00056 double getDoubleTime(struct timeval& time)
00057 {
00058     return time.tv_sec + time.tv_usec * 1e-6;
00059 }
00060 
00061 inline
00062 double getDoubleTime()
00063 {
00064     struct timeval time;
00065     gettimeofday(&time,NULL);
00066     return getDoubleTime(time);
00067 }
00068 
00069 class NDTFrame
00070 {
00071 public:
00072     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00073 public:
00074     NDTFrame() : supportSize(3),maxVar(0.3),current_res(0.2)
00075     {
00076         ndt_map = lslgeneric::NDTMap(&idx_prototype);
00077     }
00078     virtual ~NDTFrame()
00079     {
00080     }
00081     NDTFrame(const NDTFrame &other)
00082     {
00083         other.img.copyTo(img);
00084         other.depth_img.copyTo(depth_img);
00085         kpts = other.kpts;
00086         pc_kpts = other.pc_kpts;
00087         pts = other.pts;
00088         idx_prototype = other.idx_prototype;
00089         ndt_map = other.ndt_map;
00090         supportSize = other.supportSize;
00091         cameraParams = other.cameraParams;
00092         maxVar = other.maxVar;
00093         current_res=other.current_res;
00094         other.dtors.copyTo(dtors);
00095     }
00096 
00097     void clear()
00098     {
00099         maxVar = 0;
00100         kpts.resize(0);
00101         pc_kpts.resize(0);
00102         pts.resize(0);
00103         idx_prototype = lslgeneric::CellVector();
00104         ndt_map = lslgeneric::NDTMap(&idx_prototype);
00105 
00106         //pc.resize(0);
00107         //kpts_pc_indices.resize(0);
00108     }
00109 
00110     cv::Mat img;
00111     cv::Mat depth_img;
00112     size_t supportSize;
00113     double maxVar;
00114     double current_res;
00115     lslgeneric::DepthCamera<pcl::PointXYZ> cameraParams;
00116     std::vector<cv::KeyPoint> kpts;
00117     pcl::PointCloud<pcl::PointXYZ> pc_kpts; //cloud containing only keypoints
00119     std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > pts;
00120 
00121     lslgeneric::CellVector idx_prototype;
00122     lslgeneric::NDTMap ndt_map;
00123 
00124     const pcl::PointXYZ& getKeyPointCenter(int keyPointIdx)
00125     {
00126         //const std::vector<size_t> &indices = kpts_pc_indices[keyPointIdx];
00127         const pcl::PointXYZ &pt = pc_kpts[keyPointIdx]; // TODO - The first points is the centre only if the centre point is invalid...
00128         return pt;
00129     }
00130 
00131     void assignPts()
00132     {
00133         if(pc_kpts.size() == 0)
00134             computeNDT();
00135         pts.resize(pc_kpts.size());
00136         for (size_t i = 0; i < pc_kpts.size(); i++)
00137         {
00138             const pcl::PointXYZ& pt = pc_kpts[i];
00139             pts[i].head(3) = Eigen::Vector3d(pt.x,pt.y,pt.z);
00140             pts[i](3) = 1.0;
00141             //std::cout<<"keypoint "<<i<<" at "<<pts[i].transpose()<<std::endl;
00142         }
00143     }
00144 
00145     void computeNDT(bool estimateDI = false, bool nonMean = false)
00146     {
00147         if(kpts.size() > 0)
00148         {
00149             //double t1 = getDoubleTime();
00150             pc_kpts = ndt_map.loadDepthImageFeatures(depth_img,kpts,supportSize,maxVar,cameraParams,estimateDI,nonMean);
00151             //double t2 = getDoubleTime();
00152             //std::cout<<"computing ndt took (features)"<<t2-t1<<std::endl;
00153         }
00154         else
00155         {
00156             lslgeneric::LazyGrid idx_prototype_grid(current_res);
00157             ndt_map = lslgeneric::NDTMap(&idx_prototype_grid);
00158             //double t1 = getDoubleTime();
00159             ndt_map.loadDepthImage(depth_img,cameraParams);
00160             ndt_map.computeNDTCells();
00161             //double t2 = getDoubleTime();
00162             //std::cout<<"computing ndt took (grid)"<<t2-t1<<std::endl;
00163 
00164         }
00165         //ndt_map.computeNDTCells();
00166         //double t3 = getDoubleTime();
00167 
00168         /*
00169          double t1 = getDoubleTime();
00170          selectKeyPointIndices();
00171          double t2 = getDoubleTime();
00172          //ndt_map.loadPointCloud(pc, kpts_pc_indices);
00173          double t3 = getDoubleTime();
00174          ndt_map.computeNDTCells();
00175          double t4 = getDoubleTime();
00176          std::cout << "selectKeyPointIndices : " << t2 - t1 << std::endl;
00177          std::cout << "loadPointCloud : " << t3 - t2 << std::endl;
00178          std::cout << "computeNDTCells : " << t4 - t3 << std::endl;
00179          std::cout << "kpts_pc_indices.size() : " << kpts_pc_indices.size() << std::endl;
00180         */
00181     }
00182     /*
00183     void createKeyPointCloud()
00184     {
00185         pc_kpts.clear();
00186         size_t sz = 1;
00187         pcl::PointCloud<PointT> pc_kpts_loc;
00188         std::vector<cv::KeyPoint> good_kpts;
00189         //lslgeneric::CellVector<PointT> *cv = dynamic_cast<lslgeneric::CellVector<PointT> *>(ndt_map->getMyIndex());
00190 
00191         for (size_t i = 0; i < kpts.size(); i++)
00192         {
00193       cameraParams.computePointsAtIndex(depth_img,kpts[i],sz,pc_kpts_loc);
00194       PointT pt = pc_kpts_loc[0];
00195       if(std::isnan(pt.x) || std::isnan(pt.y) || std::isnan(pt.z))
00196         continue;
00197 
00198       good_kpts.push_back(kpts[i]);
00199       pc_kpts.push_back(pt);
00200         }
00201         kpts.clear();
00202         kpts.resize(0);
00203         kpts = good_kpts;
00204     } */
00205 
00206     pcl::PointCloud<pcl::PointXYZRGB> getColoredPointCloud()
00207     {
00208         lslgeneric::DepthCamera<pcl::PointXYZRGB> cameraParamsLocal (cameraParams.fx,cameraParams.fy,cameraParams.cx,
00209                 cameraParams.cy,cameraParams.dist,cameraParams.ds, cameraParams.isFloatImg);
00210         cameraParamsLocal.setupDepthPointCloudLookUpTable(depth_img.size());
00211 
00212         pcl::PointCloud<pcl::PointXYZRGB> cloud; //(new pcl::PointCloud<pcl::PointXYZRGB>);
00213         cameraParamsLocal.convertDepthImageToPointCloud(depth_img,cloud);
00214 
00215         size_t w = img.size().width;
00216         size_t h = img.size().height;
00217         size_t idx = 0;
00218         cloud.width = w;
00219         cloud.height = h;
00220         cloud.is_dense = true;
00221         const uchar* pimg = img.ptr<uchar>(0);
00222         std::cout<<"img channels "<<img.channels()<<std::endl;
00223         pcl::PointXYZRGB color;
00224         //int r=0, g=0, b=0;
00225         uint8_t r = 0, g = 0, b = 0;
00226 
00227         for( size_t i =0; i<h; i++)
00228         {
00229             for( size_t j =0; j<w; j++)
00230             {
00231                 if(img.channels() == 3)
00232                 {
00233                     const cv::Vec3b& bgr = img.at<cv::Vec3b>((int)i,(int)j);
00234                     r = bgr[0];
00235                     g = bgr[1];
00236                     b = bgr[2];
00237 
00238                     idx = 3*(i * w + j);
00239                     /*                  r = pimg[idx];
00240                                         g = pimg[idx+1];
00241                                         b = pimg[idx+2];*/
00242                 }
00243                 else if (img.channels() == 1)
00244                 {
00245                     idx = (i * w + j);
00246                     r = pimg[idx];
00247                     g = pimg[idx];
00248                     b = pimg[idx];
00249                 }
00250 
00251 //                  std::cout<<r<<" "<<g<<" "<<b<<std::endl;
00252 //                  uint32_t rgb = ((uint32_t)r << 16 | (uint32_t)g << 8 | (uint32_t)b);
00253                 pcl::PointXYZRGB &color = cloud.points[idx];
00254                 //color.rgb = *reinterpret_cast<float*>(&rgb);
00255                 color.r = r;
00256                 color.g = g;
00257                 color.b = b;
00258 //                  std::cout<<color.r<<" "<<color.g<<" "<<color.b<<" "<<color.rgb<<std::endl;
00259 
00260 //                  cloud.at(j,i) = color;
00261                 /*
00262                                     color = getPCLColor(r,g,b);
00263                                     color.r = r;
00264                                     color.g = g;
00265                                     color.b = b;
00266                                     std::cout<<color.r<<" "<<color.g<<" "<<color.b<<" "<<color.rgb<<std::endl;
00267                                     cloud->at(j,i).rgb = color.rgb;
00268                                     cloud->at(j,i).r = r;
00269                                     cloud->at(j,i).g = g;
00270                                     cloud->at(j,i).b = b;
00271                 */
00272             }
00273         }
00274         return cloud;
00275     }
00276 
00277     cv::Mat dtors;
00278 
00279     //int nbPoints;
00280     //pcl::PointCloud<PointT> pc;
00281     //std::vector<std::vector<size_t> > kpts_pc_indices; //indeces of the keypoints inside the point cloud - not needed
00282     // Only to use with an initial alignment (simply a sparser NDTMap with non-grid Gaussians based on the keypoints).
00283     // Only used to define the spatial structure of the ndt_map.
00284 
00285     /*
00286           void removeFiniteIndices(std::vector<size_t> &indices)
00287                {
00288                     std::vector<size_t> tmp;
00289                     for (size_t i = 0; i < indices.size(); i++)
00290                     {
00291                          const PointT& pt = pc[indices[i]];
00292                          if (!std::isfinite(pt.x) ||
00293                              !std::isfinite(pt.y) ||
00294                              !std::isfinite(pt.z))
00295                          {
00296 
00297                          }
00298                          else
00299                          {
00300                               tmp.push_back(indices[i]);
00301                          }
00302                     }
00303                     indices = tmp;
00304                }
00305 
00306           void selectKeyPointIndices()
00307                {
00308                     size_t nkpts = kpts.size();
00309                     kpts_pc_indices.reserve(nkpts);
00310                     std::vector<cv::KeyPoint> good_kpts;
00311                     for (size_t i=0; i<nkpts; i++)
00312                     {
00313 
00314                          std::vector<size_t> indices;
00315                          selectIndicesAroundKeyPoint(kpts[i], pc, nbPoints, indices);
00316                          removeFiniteIndices(indices);
00317 
00318                          // Compute the NDTCell here...
00319                          lslgeneric::NDTCell<PointT> tmp;
00320                          for (size_t j = 0; j < indices.size(); j++)
00321                          {
00322                               tmp.points_.push_back(pc[indices[j]]);
00323                          }
00324                          tmp.computeGaussian();
00325                          if (tmp.hasGaussian_)
00326                          {
00327                               kpts_pc_indices.push_back(indices);
00328                               good_kpts.push_back(kpts[i]);
00329                               idx_prototype.addCell(tmp.copy());
00330                          }
00331                          else
00332                          {
00333     //                        assert(false);
00334                          }
00335                     }
00336                     kpts = good_kpts; // Probably a bit inefficient- but now we only have good ones in the vector and can have a one to one mapping without having to check for NaN's / having a separate boolean vector indicating if it is a good point etc.
00337                     std::cout << "kpts.size() : " << kpts.size() << std::endl;
00338                     std::cout << "idx_prototype.size() : " << idx_prototype.size() << std::endl;
00339                     assert((int)kpts.size() == idx_prototype.size());
00340                }
00341     */
00342 };
00343 
00344 
00345 class PoseEstimator
00346 {
00347 public:
00348     PoseEstimator(int NRansac,
00349                   double maxidx, double maxidd);
00350     size_t estimate(const NDTFrame &f0, const NDTFrame &f1);
00351     size_t estimate(const NDTFrame &f0, const NDTFrame &f1, const std::vector<cv::DMatch>& matches);
00352 
00353     const std::vector<cv::DMatch>& getInliers() const
00354     {
00355         return inliers;
00356     }
00357 
00358     void matchFrames(const NDTFrame& f0, const NDTFrame& f2, std::vector<cv::DMatch>& fwd_matches);
00359 
00360     inline Eigen::Affine3f getTransform()
00361     {
00362         Eigen::Affine3f transl_transform = (Eigen::Affine3f)Eigen::Translation3f(trans[0], trans[1], trans[2]);
00363         Eigen::Affine3f rot_transform = (Eigen::Affine3f)Eigen::Matrix3f(rot.cast<float>());
00364         return transl_transform*rot_transform;
00365     }
00366 
00367     // all matches and inliers
00368     std::vector<cv::DMatch> matches; 
00369     std::vector<cv::DMatch> inliers; 
00370 
00371     int numRansac;
00372 
00374     bool windowed;
00375 
00377     double maxInlierXDist2, maxInlierDDist2;
00378 
00379     double maxDist;
00380     double minDist;
00381 
00383     cv::Ptr<cv::DescriptorMatcher> matcher;
00384     int wx /*< Width of matching window.*/, wy /*< Height of matching window*/;
00385 
00386     // transform
00387     Eigen::Matrix3d rot; 
00388     Eigen::Quaterniond quat;
00389     Eigen::Vector3d trans; 
00390 
00391     bool projectMatches;
00392 };
00393 
00394 
00395 } // namespace
00396 
00397 //#include <ndt_feature_reg/impl/ndt_frame.hpp>
00398 
00399 #endif


ndt_feature_reg
Author(s): Henrik Andreasson, Todor Stoyanov, Jari Saarinen
autogenerated on Wed Aug 26 2015 15:25:07