discrete_depth_distortion_model.h
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 #ifndef DISCRETE_DEPTH_DISTORTION_MODEL_H
00031 #define DISCRETE_DEPTH_DISTORTION_MODEL_H
00032 
00033 #include <assert.h>
00034 #include <vector>
00035 #include <set>
00036 #include <Eigen/Core>
00037 #include <opencv2/opencv.hpp>
00038 #include <rtabmap/utilite/UMutex.h>
00039 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00040 
00041 namespace clams
00042 {
00043   class RTABMAP_EXP DiscreteFrustum
00044   {
00045   public:
00046     DiscreteFrustum(int smoothing = 1, double bin_depth = 1.0, double max_dist = 10.0);
00049     void addExample(double ground_truth, double measurement);
00050     int index(double z) const;
00051     void undistort(double* z) const;
00052     void interpolatedUndistort(double* z) const;
00053     void serialize(std::ostream& out, bool ascii) const;
00054     void deserialize(std::istream& in, bool ascii);
00055   
00056   protected:
00057     double max_dist_;
00058     int num_bins_;
00059     double bin_depth_;
00060     Eigen::VectorXf counts_;
00061     Eigen::VectorXf total_numerators_;
00062     Eigen::VectorXf total_denominators_;
00063     Eigen::VectorXf multipliers_;
00064 
00065     friend class DiscreteDepthDistortionModel;
00066   };
00067 
00068   class RTABMAP_EXP DiscreteDepthDistortionModel
00069   {
00070   public:
00071     // returns all divisors of num
00072     static std::set<size_t> getDivisors(const size_t &num);
00073 
00074     // returns divisor from divisors closest to ref
00075     static size_t getClosestToRef(const std::set<size_t> &divisors, const double &ref);
00076 
00077     // sets bin_width and bin_height to appropriate values
00078     static void getBinSize(const size_t &width, const size_t &height, size_t &bin_width, size_t &bin_height);
00079 
00080   public:
00081     DiscreteDepthDistortionModel() :
00082         width_(0),
00083                 height_(0),
00084                 bin_width_(0),
00085                 bin_height_(0),
00086                 bin_depth_(0),
00087                 num_bins_x_(0),
00088                 num_bins_y_(0),
00089                 training_samples_(0)
00090     {}
00091     virtual ~DiscreteDepthDistortionModel();
00092     DiscreteDepthDistortionModel(int width, int height, int bin_width = 8, int bin_height = 6, double bin_depth = 2.0, int smoothing = 1, double max_depth = 10.0);
00093     DiscreteDepthDistortionModel(const DiscreteDepthDistortionModel& other);
00094     DiscreteDepthDistortionModel& operator=(const DiscreteDepthDistortionModel& other);
00095     void undistort(cv::Mat & depth) const;
00098     size_t accumulate(const cv::Mat& ground_truth, const cv::Mat& measurement);
00099     void addExample(int v, int u, double ground_truth, double measurement);
00100     void save(const std::string& path) const;
00101         void load(const std::string& path);
00102         void serialize(std::ostream& out, bool ascii) const;
00103         void deserialize(std::istream& in, bool ascii);
00104     cv::Mat visualize(const std::string& path = "") const;
00105 
00106     int getWidth() const {return width_;}
00107     int getHeight() const {return height_;}
00108     size_t getTrainingSamples() const {return training_samples_;}
00109     bool isValid() const
00110     {
00111         return !frustums_.empty();
00112     }
00113 
00114   protected:
00116     int width_;
00118     int height_;
00120     int bin_width_;
00122     int bin_height_;
00124     double bin_depth_;
00125     int num_bins_x_;
00126     int num_bins_y_;
00128     std::vector< std::vector<DiscreteFrustum*> > frustums_;
00129 
00130     size_t training_samples_;
00131 
00132     void deleteFrustums();
00133     DiscreteFrustum& frustum(int y, int x);
00134     const DiscreteFrustum& frustum(int y, int x) const;
00135 
00136     UMutex mutex_;
00137   };
00138 
00139 }  // namespace clams
00140 
00141 #endif // DISCRETE_DEPTH_DISTORTION_MODEL_H


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