frame_projector.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2013, Alex Teichman and Stephen Miller (Stanford University)
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the <organization> nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 
00027 RTAB-Map integration: Mathieu Labbe
00028 */
00029 
00030 #include "rtabmap/core/clams/frame_projector.h"
00031 #include <rtabmap/utilite/ULogger.h>
00032 #include <rtabmap/core/util3d_transforms.h>
00033 #include <rtabmap/core/util3d.h>
00034 #include <opencv2/highgui/highgui.hpp>
00035 #include <opencv2/imgproc/imgproc.hpp>
00036 
00037 using namespace std;
00038 using namespace Eigen;
00039 
00040 namespace clams
00041 {
00042   FrameProjector::FrameProjector(const rtabmap::CameraModel & model) :
00043     model_(model)
00044   {
00045           UASSERT(model.isValidForReprojection());
00046   }
00047 
00048   // pcd is in /map frame
00049   FrameProjector::RangeIndex FrameProjector::cloudToRangeIndex(const pcl::PointCloud<pcl::PointXYZ>::Ptr & pcd) const
00050   {
00051           int height = model_.imageHeight();
00052           int width = model_.imageWidth();
00053     RangeIndex ind;
00054     if((int)ind.size() != height)
00055       ind.resize(height);
00056     for(size_t y = 0; y < ind.size(); ++y)
00057       if((int)ind[y].size() != width)
00058         ind[y].resize(width);
00059     for(size_t y = 0; y < ind.size(); ++y) {
00060       for(size_t x = 0; x < ind[y].size(); ++x) { 
00061         ind[y][x].clear();
00062         ind[y][x].reserve(10);
00063       }
00064     }
00065 
00066     rtabmap::Transform t = model_.localTransform().inverse();
00067 
00068     ProjectivePoint ppt;
00069     for(size_t i = 0; i < pcd->size(); ++i) {
00070       if(!isFinite(pcd->at(i)))
00071         continue;
00072       ppt = reproject(rtabmap::util3d::transformPoint(pcd->at(i), t));
00073       if(ppt.z_ == 0 || !(ppt.u_ >= 0 && ppt.v_ >= 0 && ppt.u_ < width && ppt.v_ < height))
00074         continue;
00075       ind[ppt.v_][ppt.u_].push_back(ppt.z_);
00076     }
00077     return ind;
00078   }
00079 
00080   pcl::PointXYZ FrameProjector::project(const ProjectivePoint& ppt) const
00081   {
00082          UASSERT(ppt.u_ >= 0 && ppt.v_ >= 0 && ppt.u_ < model_.imageWidth() && ppt.v_ < model_.imageHeight());
00083 
00084          pcl::PointXYZ pt;
00085 
00086          model_.project(ppt.u_, ppt.v_, ppt.z_, pt.x, pt.y, pt.z);
00087     return pt;
00088   }
00089   
00090   ProjectivePoint FrameProjector::reproject(const pcl::PointXYZ & pt) const
00091   {
00092          UASSERT(isFinite(pt));
00093 
00094          ProjectivePoint ppt;
00095 
00096          if(pt.z > 0)
00097          {
00098                  model_.reproject(pt.x, pt.y, pt.z, ppt.u_, ppt.v_);
00099                  ppt.z_ = pt.z;
00100          }
00101 
00102     return ppt;
00103   }
00104   
00105   cv::Mat FrameProjector::estimateMapDepth(
00106                   const pcl::PointCloud<pcl::PointXYZ>::Ptr & map,
00107                   const rtabmap::Transform & transform,
00108           const cv::Mat& measurement,
00109                   double coneRadius,
00110                   double coneStdevThresh) const
00111   {
00112         cv::Mat estimate = cv::Mat::zeros(measurement.size(), CV_32FC1);
00113 
00114     // -- Get the depth index.
00115      pcl::PointCloud<pcl::PointXYZ>::Ptr transformed = rtabmap::util3d::transformPointCloud(map, transform);
00116     RangeIndex rindex = cloudToRangeIndex(transformed);
00117 
00118     // -- Compute the edge-of-map mask.
00119     cv::Mat naive_mapframe = rtabmap::util3d::projectCloudToCamera(model_.imageSize(), model_.K(), transformed, model_.localTransform());
00120     const cv::Mat& measurement_depth = measurement;
00121     const cv::Mat& naive_mapdepth = naive_mapframe;
00122     cv::Mat1b mask(measurement_depth.rows, measurement_depth.cols);
00123     mask = 0;
00124     for(int y = 0; y < mask.rows; ++y)
00125       for(int x = 0; x < mask.cols; ++x)
00126         if(naive_mapdepth.at<float>(y, x) != 0)
00127           mask(y, x) = 255;
00128 
00129     cv::dilate(mask, mask, cv::Mat(), cv::Point(-1, -1), 4);
00130     cv::erode(mask, mask, cv::Mat(), cv::Point(-1, -1), 15);
00131 
00132     bool isInMM = measurement_depth.type() == CV_16UC1;
00133 
00134     // -- Main loop: for all points in the image...
00135     ProjectivePoint ppt;
00136     for(ppt.v_ = 0; ppt.v_ < measurement_depth.rows; ++ppt.v_) {
00137       for(ppt.u_ = 0; ppt.u_ < measurement_depth.cols; ++ppt.u_) {
00138 
00139           float value = isInMM?float(measurement_depth.at<unsigned short>(ppt.v_, ppt.u_))*0.001f:measurement_depth.at<float>(ppt.v_, ppt.u_);
00140 
00141         // -- Reject points with no data.
00142         if(value == 0)
00143           continue;
00144         if(naive_mapdepth.at<float>(ppt.v_, ppt.u_) == 0)
00145           continue;
00146         
00147         // -- Reject points on the edge of the map.
00148         if(mask(ppt.v_, ppt.u_) == 0)
00149           continue;
00150 
00151         // -- Find nearby points in the cone to get a good estimate of the map depth.
00152         double mean = 0;
00153         double stdev = 0;
00154         //double stdev_thresh = numeric_limits<double>::max();
00155         bool valid = coneFit(
00156                         naive_mapdepth.size(),
00157                         rindex,
00158                                 ppt.u_,
00159                                 ppt.v_,
00160                                 coneRadius,
00161                                 value,
00162                                 &mean,
00163                                 &stdev);
00164         if(!valid)
00165           continue;
00166         if(stdev > coneStdevThresh)
00167           continue;
00168 
00169         estimate.at<float>(ppt.v_, ppt.u_) = mean;
00170       }
00171     }
00172     return estimate;
00173   }
00174 
00175   bool FrameProjector::coneFit(const cv::Size& imageSize, const RangeIndex& rindex,
00176                                 int uc, int vc, double radius, double measurement_depth,
00177                                 double* mean, double* stdev) const
00178   {
00179     pcl::PointXYZ pt_center, pt_ul, pt_lr;
00180     ProjectivePoint ppt, ppt_ul, ppt_lr;
00181     ppt.u_ = uc;
00182     ppt.v_ = vc;
00183     ppt.z_ = measurement_depth;
00184     pt_center = project(ppt);
00185 
00186     pt_ul = pt_center;
00187     pt_lr = pt_center;
00188     pt_ul.x -= radius;
00189     pt_ul.y -= radius;
00190     pt_lr.x += radius;
00191     pt_lr.y += radius;
00192 
00193     if(!pcl::isFinite(pt_ul) || !pcl::isFinite(pt_lr))
00194     {
00195         return false;
00196     }
00197 
00198     ppt_ul = reproject(pt_ul);
00199     ppt_lr = reproject(pt_lr);
00200     if(ppt_ul.z_ == 0 || !(ppt_ul.u_ >= 0 && ppt_ul.v_ >= 0 && ppt_ul.u_ < imageSize.width && ppt_ul.v_ < imageSize.height))
00201       return false;
00202     if(ppt_lr.z_ == 0 || !(ppt_lr.u_ >= 0 && ppt_lr.v_ >= 0 && ppt_lr.u_ < imageSize.width && ppt_lr.v_ < imageSize.height))
00203       return false;
00204 
00205     int min_u = ppt_ul.u_;
00206     int max_u = ppt_lr.u_;
00207     int min_v = ppt_ul.v_;
00208     int max_v = ppt_lr.v_;
00209 
00210     *mean = 0;
00211     double num = 0;
00212     for(ppt.u_ = min_u; ppt.u_ <= max_u; ++ppt.u_) {
00213       for(ppt.v_ = min_v; ppt.v_ <= max_v; ++ppt.v_) {
00214         const vector<double>& vals = rindex[ppt.v_][ppt.u_];
00215         for(size_t i = 0; i < vals.size(); ++i) {
00216           double mult = vals[i] / measurement_depth;
00217           if(mult > MIN_MULT && mult < MAX_MULT) {
00218             *mean += vals[i];
00219             ++num;
00220           }
00221         }
00222       }
00223     }
00224     if(num == 0)
00225       return false;
00226     *mean /= num;
00227 
00228     double var = 0;
00229     for(ppt.u_ = min_u; ppt.u_ <= max_u; ++ppt.u_) {
00230       for(ppt.v_ = min_v; ppt.v_ <= max_v; ++ppt.v_) {
00231         const vector<double>& vals = rindex[ppt.v_][ppt.u_];
00232         for(size_t i = 0; i < vals.size(); ++i) {
00233           double mult = vals[i] / measurement_depth;
00234           if(mult > MIN_MULT && mult < MAX_MULT)
00235             var += (vals[i] - *mean) * (vals[i] - *mean);
00236         }
00237       }
00238     }
00239     var /= num;
00240     
00241     *stdev = sqrt(var);
00242     return true;
00243   }
00244   
00245 }  // namespace clams
00246 


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:20