discrete_depth_distortion_model.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/discrete_depth_distortion_model.h"
00031 #include "rtabmap/core/clams/frame_projector.h"
00032 #include <rtabmap/utilite/ULogger.h>
00033 #include <rtabmap/utilite/UMath.h>
00034 #include <rtabmap/utilite/UFile.h>
00035 #include "eigen_extensions/eigen_extensions.h"
00036 
00037 using namespace std;
00038 using namespace Eigen;
00039 
00040 namespace clams
00041 {
00042 
00043   DiscreteFrustum::DiscreteFrustum(int smoothing, double bin_depth, double max_dist) :
00044     max_dist_(max_dist),
00045     bin_depth_(bin_depth)
00046   {
00047     UASSERT(max_dist_ >= bin_depth_);
00048     UASSERT(bin_depth_>0.0);
00049     UASSERT(smoothing>=1);
00050     num_bins_ = ceil(max_dist_ / bin_depth_);
00051     counts_ = VectorXf::Ones(num_bins_) * smoothing;
00052     total_numerators_ = VectorXf::Ones(num_bins_) * smoothing;
00053     total_denominators_ = VectorXf::Ones(num_bins_) * smoothing;
00054     multipliers_ = VectorXf::Ones(num_bins_);
00055   }
00056 
00057   void DiscreteFrustum::addExample(double ground_truth, double measurement)
00058   {
00059     double mult = ground_truth / measurement;
00060     if(mult > MAX_MULT || mult < MIN_MULT)
00061       return;
00062   
00063     int idx = min(num_bins_ - 1, (int)floor(measurement / bin_depth_));
00064     UASSERT(idx >= 0);
00065 
00066     total_numerators_(idx) += ground_truth * ground_truth;
00067     total_denominators_(idx) += ground_truth * measurement;
00068     ++counts_(idx);
00069     multipliers_(idx) = total_numerators_(idx) / total_denominators_(idx);
00070   }
00071 
00072   inline int DiscreteFrustum::index(double z) const
00073   {
00074     return min(num_bins_ - 1, (int)floor(z / bin_depth_));
00075   }
00076   
00077   inline void DiscreteFrustum::undistort(double* z) const
00078   {
00079     *z *= multipliers_.coeffRef(index(*z));
00080   }
00081 
00082   void DiscreteFrustum::interpolatedUndistort(double* z) const
00083   {
00084     int idx = index(*z);
00085     double start = bin_depth_ * idx;
00086     int idx1;
00087     if(*z - start < bin_depth_ / 2)
00088       idx1 = idx;
00089     else
00090       idx1 = idx + 1;
00091     int idx0 = idx1 - 1;
00092     if(idx0 < 0 || idx1 >= num_bins_ || counts_(idx0) < 50 || counts_(idx1) < 50) {
00093       undistort(z);
00094       return;
00095     }
00096 
00097     double z0 = (idx0 + 1) * bin_depth_ - bin_depth_ * 0.5;
00098     double coeff1 = (*z - z0) / bin_depth_;
00099     double coeff0 = 1.0 - coeff1;
00100     double mult = coeff0 * multipliers_.coeffRef(idx0) + coeff1 * multipliers_.coeffRef(idx1);
00101     *z *= mult;
00102   }
00103 
00104   void DiscreteFrustum::serialize(std::ostream& out, bool ascii) const
00105     {
00106           if(ascii)
00107           {
00108                 eigen_extensions::serializeScalarASCII(max_dist_, out);
00109                 eigen_extensions::serializeScalarASCII(num_bins_, out);
00110                 eigen_extensions::serializeScalarASCII(bin_depth_, out);
00111                 eigen_extensions::serializeASCII(counts_, out);
00112                 eigen_extensions::serializeASCII(total_numerators_, out);
00113                 eigen_extensions::serializeASCII(total_denominators_, out);
00114                 eigen_extensions::serializeASCII(multipliers_, out);
00115           }
00116           else
00117           {
00118                 eigen_extensions::serializeScalar(max_dist_, out);
00119                 eigen_extensions::serializeScalar(num_bins_, out);
00120                 eigen_extensions::serializeScalar(bin_depth_, out);
00121                 eigen_extensions::serialize(counts_, out);
00122                 eigen_extensions::serialize(total_numerators_, out);
00123                 eigen_extensions::serialize(total_denominators_, out);
00124                 eigen_extensions::serialize(multipliers_, out);
00125           }
00126     }
00127 
00128     void DiscreteFrustum::deserialize(std::istream& in, bool ascii)
00129     {
00130         if(ascii)
00131         {
00132                         eigen_extensions::deserializeScalarASCII(in, &max_dist_);
00133                         eigen_extensions::deserializeScalarASCII(in, &num_bins_);
00134                         eigen_extensions::deserializeScalarASCII(in, &bin_depth_);
00135                         eigen_extensions::deserializeASCII(in, &counts_);
00136                         eigen_extensions::deserializeASCII(in, &total_numerators_);
00137                         eigen_extensions::deserializeASCII(in, &total_denominators_);
00138                         eigen_extensions::deserializeASCII(in, &multipliers_);
00139         }
00140         else
00141         {
00142                         eigen_extensions::deserializeScalar(in, &max_dist_);
00143                         eigen_extensions::deserializeScalar(in, &num_bins_);
00144                         eigen_extensions::deserializeScalar(in, &bin_depth_);
00145                         eigen_extensions::deserialize(in, &counts_);
00146                         eigen_extensions::deserialize(in, &total_numerators_);
00147                         eigen_extensions::deserialize(in, &total_denominators_);
00148                         eigen_extensions::deserialize(in, &multipliers_);
00149         }
00150       UDEBUG("Frustum: max_dist=%f", max_dist_);
00151       UDEBUG("Frustum: num_bins=%d", num_bins_);
00152       UDEBUG("Frustum: bin_depth=%f", bin_depth_);
00153       UDEBUG("Frustum: counts=%d", counts_.rows());
00154       UDEBUG("Frustum: total_numerators=%d", total_numerators_.rows());
00155       UDEBUG("Frustum: total_denominators=%d", total_denominators_.rows());
00156       UDEBUG("Frustum: multipliers=%d", multipliers_.rows());
00157     }
00158 
00159   std::set<size_t> DiscreteDepthDistortionModel::getDivisors(const size_t &num)
00160   {
00161     std::set<size_t> divisors;
00162     for(size_t i = 1; i <= num; i++)
00163     {
00164       if(num % i == 0)
00165       {
00166         divisors.insert(i);
00167       }
00168     }
00169     return divisors;
00170   }
00171 
00172   size_t DiscreteDepthDistortionModel::getClosestToRef(const std::set<size_t> &divisors, const double &ref)
00173   {
00174     std::set<size_t>::iterator low, prev;
00175     low = divisors.lower_bound(ref);
00176     if(low == divisors.end())
00177     {
00178       return *(--divisors.end());
00179     }
00180     else if(low == divisors.begin())
00181     {
00182       return *low;
00183     }
00184     else
00185     {
00186       prev = low;
00187       --prev;
00188       if((ref - *prev) <= (*low - ref))
00189       {
00190         return *prev;
00191       }
00192       else
00193       {
00194         return *low;
00195       }
00196     }
00197   }
00198 
00199   void DiscreteDepthDistortionModel::getBinSize(const size_t &width, const size_t &height, size_t &bin_width, size_t &bin_height) {
00200     double ratio = width / static_cast<double>(height);
00201     std::set<size_t> divisors = getDivisors(width);
00202     double ref_bin_width = 8;
00203     bin_width = getClosestToRef(divisors, ref_bin_width);
00204     divisors = getDivisors(height);
00205     double ref_bin_height = ref_bin_width / ratio;
00206     bin_height = getClosestToRef(divisors, ref_bin_height);
00207   }
00208 
00209 
00210   DiscreteDepthDistortionModel::DiscreteDepthDistortionModel(const DiscreteDepthDistortionModel& other)
00211   {
00212     *this = other;
00213   }
00214 
00215   DiscreteDepthDistortionModel& DiscreteDepthDistortionModel::operator=(const DiscreteDepthDistortionModel& other)
00216   {
00217     width_ = other.width_;
00218     height_ = other.height_;
00219     bin_width_ = other.bin_width_;
00220     bin_height_ = other.bin_height_;
00221     bin_depth_ = other.bin_depth_;
00222     num_bins_x_ = other.num_bins_x_;
00223     num_bins_y_ = other.num_bins_y_;
00224     training_samples_ = other.training_samples_;
00225   
00226     frustums_ = other.frustums_;
00227     for(size_t i = 0; i < frustums_.size(); ++i)
00228       for(size_t j = 0; j < frustums_[i].size(); ++j)
00229         frustums_[i][j] = new DiscreteFrustum(*other.frustums_[i][j]);
00230 
00231     return *this;
00232   }
00233 
00234   DiscreteDepthDistortionModel::DiscreteDepthDistortionModel(int width, int height,
00235                                                              int bin_width, int bin_height,
00236                                                              double bin_depth,
00237                                                              int smoothing,
00238                                                                                                                          double max_depth) :
00239     width_(width),
00240     height_(height),
00241     bin_width_(bin_width),
00242     bin_height_(bin_height),
00243     bin_depth_(bin_depth)
00244   {
00245     UASSERT(width_ % bin_width_ == 0);
00246     UASSERT(height_ % bin_height_ == 0);
00247 
00248     num_bins_x_ = width_ / bin_width_;
00249     num_bins_y_ = height_ / bin_height_;
00250   
00251     frustums_.resize(num_bins_y_);
00252     for(size_t i = 0; i < frustums_.size(); ++i) {
00253       frustums_[i].resize(num_bins_x_, NULL);
00254       for(size_t j = 0; j < frustums_[i].size(); ++j)
00255         frustums_[i][j] = new DiscreteFrustum(smoothing, bin_depth, max_depth);
00256     }
00257 
00258     training_samples_ = 0;
00259   }
00260 
00261   void DiscreteDepthDistortionModel::deleteFrustums()
00262   {
00263           UDEBUG("");
00264     for(size_t y = 0; y < frustums_.size(); ++y)
00265       for(size_t x = 0; x < frustums_[y].size(); ++x)
00266         if(frustums_[y][x])
00267           delete frustums_[y][x];
00268     training_samples_ = 0;
00269   }
00270 
00271   DiscreteDepthDistortionModel::~DiscreteDepthDistortionModel()
00272   {
00273     deleteFrustums();
00274   }
00275 
00276   void DiscreteDepthDistortionModel::undistort(cv::Mat & depth) const
00277   {
00278     UASSERT(width_ == depth.cols);
00279     UASSERT(height_ ==depth.rows);
00280     UASSERT(depth.type() == CV_16UC1 || depth.type() == CV_32FC1);
00281     if(depth.type() == CV_32FC1)
00282     {
00283                 #pragma omp parallel for
00284                 for(int v = 0; v < height_; ++v) {
00285                   for(int u = 0; u < width_; ++u) {
00286                          float & z = depth.at<float>(v, u);
00287                         if(uIsNan(z) || z == 0.0f)
00288                           continue;
00289                         double zf = z;
00290                         frustum(v, u).interpolatedUndistort(&zf);
00291                         z = zf;
00292                   }
00293                 }
00294     }
00295     else
00296     {
00297                 #pragma omp parallel for
00298                 for(int v = 0; v < height_; ++v) {
00299                   for(int u = 0; u < width_; ++u) {
00300                     unsigned short & z = depth.at<unsigned short>(v, u);
00301                         if(uIsNan(z) || z == 0)
00302                           continue;
00303                         double zf = z * 0.001;
00304                         frustum(v, u).interpolatedUndistort(&zf);
00305                         z = zf*1000;
00306                   }
00307                 }
00308     }
00309   }
00310 
00311   void DiscreteDepthDistortionModel::addExample(int v, int u, double ground_truth, double measurement)
00312   {
00313     frustum(v, u).addExample(ground_truth, measurement);
00314   }
00315 
00316   size_t DiscreteDepthDistortionModel::accumulate(const cv::Mat& ground_truth,
00317                                                   const cv::Mat& measurement)
00318   {
00319     UASSERT(width_ == ground_truth.cols);
00320     UASSERT(height_ == ground_truth.rows);
00321     UASSERT(width_ == measurement.cols);
00322     UASSERT(height_ == measurement.rows);
00323     UASSERT(ground_truth.type() == CV_16UC1 || ground_truth.type() == CV_32FC1);
00324     UASSERT(measurement.type() == CV_16UC1 || measurement.type() == CV_32FC1);
00325 
00326     bool isGroundTruthInMM = ground_truth.type()==CV_16UC1;
00327     bool isMeasurementInMM = measurement.type()==CV_16UC1;
00328 
00329     size_t num_training_examples = 0;
00330     for(int v = 0; v < height_; ++v) {
00331       for(int u = 0; u < width_; ++u) {
00332           float gt = isGroundTruthInMM?float(ground_truth.at<unsigned short>(v,u))*0.001:ground_truth.at<float>(v,u);
00333         if(gt == 0)
00334           continue;
00335         float meas = isMeasurementInMM?float(measurement.at<unsigned short>(v,u))*0.001:measurement.at<float>(v,u);
00336         if(meas == 0)
00337           continue;
00338 
00339         UScopeMutex sm(mutex_);
00340         frustum(v, u).addExample(gt, meas);
00341         ++num_training_examples;
00342       }
00343     }
00344 
00345     training_samples_ += num_training_examples;
00346 
00347     return num_training_examples;
00348   }
00349 
00350   void DiscreteDepthDistortionModel::load(const std::string& path)
00351     {
00352           bool ascii = UFile::getExtension(path).compare("txt") == 0;
00353       ifstream f;
00354       f.open(path.c_str(), ascii ? ios::in : ios::in | ios::binary);
00355       if(!f.is_open()) {
00356         cerr << "Failed to open " << path << endl;
00357         assert(f.is_open());
00358       }
00359       deserialize(f, ascii);
00360       f.close();
00361     }
00362 
00363     void DiscreteDepthDistortionModel::save(const std::string& path) const
00364     {
00365       bool ascii = UFile::getExtension(path).compare("txt") == 0;
00366       ofstream f;
00367       f.open(path.c_str(), ascii?ios::out: ios::out | ios::binary);
00368       if(!f.is_open()) {
00369         cerr << "Failed to open " << path << endl;
00370         assert(f.is_open());
00371       }
00372       serialize(f, ascii);
00373       f.close();
00374     }
00375 
00376     void DiscreteDepthDistortionModel::serialize(std::ostream& out, bool ascii) const
00377     {
00378       out << "DiscreteDepthDistortionModel v01" << endl;
00379       if(ascii)
00380       {
00381                 eigen_extensions::serializeScalarASCII(width_, out);
00382                 eigen_extensions::serializeScalarASCII(height_, out);
00383                 eigen_extensions::serializeScalarASCII(bin_width_, out);
00384                 eigen_extensions::serializeScalarASCII(bin_height_, out);
00385                 eigen_extensions::serializeScalarASCII(bin_depth_, out);
00386                 eigen_extensions::serializeScalarASCII(num_bins_x_, out);
00387                 eigen_extensions::serializeScalarASCII(num_bins_y_, out);
00388                 eigen_extensions::serializeScalarASCII(training_samples_, out);
00389       }
00390       else
00391       {
00392                 eigen_extensions::serializeScalar(width_, out);
00393                 eigen_extensions::serializeScalar(height_, out);
00394                 eigen_extensions::serializeScalar(bin_width_, out);
00395                 eigen_extensions::serializeScalar(bin_height_, out);
00396                 eigen_extensions::serializeScalar(bin_depth_, out);
00397                 eigen_extensions::serializeScalar(num_bins_x_, out);
00398                 eigen_extensions::serializeScalar(num_bins_y_, out);
00399                 eigen_extensions::serializeScalar(training_samples_, out);
00400       }
00401 
00402 
00403       for(int y = 0; y < num_bins_y_; ++y)
00404         for(int x = 0; x < num_bins_x_; ++x)
00405           frustums_[y][x]->serialize(out, ascii);
00406     }
00407 
00408     void DiscreteDepthDistortionModel::deserialize(std::istream& in, bool ascii)
00409     {
00410       UDEBUG("");
00411       string buf;
00412       getline(in, buf);
00413       UDEBUG("buf=%s", buf.c_str());
00414       assert(buf == "DiscreteDepthDistortionModel v01");
00415       if(ascii)
00416       {
00417           eigen_extensions::deserializeScalarASCII(in, &width_);
00418                   eigen_extensions::deserializeScalarASCII(in, &height_);
00419                   eigen_extensions::deserializeScalarASCII(in, &bin_width_);
00420                   eigen_extensions::deserializeScalarASCII(in, &bin_height_);
00421                   eigen_extensions::deserializeScalarASCII(in, &bin_depth_);
00422                   eigen_extensions::deserializeScalarASCII(in, &num_bins_x_);
00423                   eigen_extensions::deserializeScalarASCII(in, &num_bins_y_);
00424                   eigen_extensions::deserializeScalarASCII(in, &training_samples_);
00425       }
00426       else
00427       {
00428                   eigen_extensions::deserializeScalar(in, &width_);
00429                   eigen_extensions::deserializeScalar(in, &height_);
00430                   eigen_extensions::deserializeScalar(in, &bin_width_);
00431                   eigen_extensions::deserializeScalar(in, &bin_height_);
00432                   eigen_extensions::deserializeScalar(in, &bin_depth_);
00433                   eigen_extensions::deserializeScalar(in, &num_bins_x_);
00434                   eigen_extensions::deserializeScalar(in, &num_bins_y_);
00435                   eigen_extensions::deserializeScalar(in, &training_samples_);
00436       }
00437       UINFO("Distortion Model: width=%d", width_);
00438       UINFO("Distortion Model: height=%d", height_);
00439       UINFO("Distortion Model: bin_width=%d", bin_width_);
00440       UINFO("Distortion Model: bin_height=%d", bin_height_);
00441       UINFO("Distortion Model: bin_depth=%f", bin_depth_);
00442       UINFO("Distortion Model: num_bins_x=%d", num_bins_x_);
00443       UINFO("Distortion Model: num_bins_y=%d", num_bins_y_);
00444       UINFO("Distortion Model: training_samples=%d", training_samples_);
00445       deleteFrustums();
00446       frustums_.resize(num_bins_y_);
00447       for(size_t y = 0; y < frustums_.size(); ++y) {
00448         frustums_[y].resize(num_bins_x_, NULL);
00449         for(size_t x = 0; x < frustums_[y].size(); ++x) {
00450                 UDEBUG("Distortion Model: Frustum[%d][%d]", y, x);
00451           frustums_[y][x] = new DiscreteFrustum;
00452           frustums_[y][x]->deserialize(in, ascii);
00453         }
00454       }
00455       UDEBUG("");
00456     }
00457 
00458   DiscreteFrustum& DiscreteDepthDistortionModel::frustum(int y, int x)
00459   {
00460     UASSERT(x >= 0 && x < width_);
00461     UASSERT(y >= 0 && y < height_);
00462     int xidx = x / bin_width_;
00463     int yidx = y / bin_height_;
00464     return (*frustums_[yidx][xidx]);
00465   }
00466 
00467   const DiscreteFrustum& DiscreteDepthDistortionModel::frustum(int y, int x) const
00468   {
00469     UASSERT(x >= 0 && x < width_);
00470     UASSERT(y >= 0 && y < height_);
00471     int xidx = x / bin_width_;
00472     int yidx = y / bin_height_;
00473     return (*frustums_[yidx][xidx]);
00474   }
00475 
00476 }  // namespace clams


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