models.h
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 
00030 #ifndef OPENCV_UTIL_MODELS_H_
00031 #define OPENCV_UTIL_MODELS_H_
00032 
00033 #include <vector>
00034 
00035 #include <opencv2/core/core.hpp>
00036 
00037 namespace swri_opencv_util
00038 {
00039 
00040   class Correspondence2d
00041   {
00042   public:
00043     typedef cv::Mat T;         // An Nx4 float matrix
00044     typedef cv::Mat M;
00045 
00046     explicit Correspondence2d(const T& data) : data_(data) {}
00047 
00048     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const = 0;
00049     int32_t GetInlierCount(const M& model, double max_error);
00050     void GetInliers(const M& model, double max_error, std::vector<uint32_t>& indices);
00051     int32_t Size() const { return data_.rows; }
00052     virtual std::string GetModelString(M& model) const { return ""; }
00053 
00054     static void CopyTo(const M& src, M& dst)
00055     {
00056       src.copyTo(dst);
00057     }
00058 
00059   protected:
00060     virtual void CalculateNorms(const M& model, cv::Mat& norms);
00061 
00062     const T& data_;
00063 
00064     // Buffer matrices to avoid repeated memory allocations.
00065     cv::Mat norms__;
00066     cv::Mat predicted__;
00067     cv::Mat delta__;
00068     cv::Mat delta_squared__;
00069     cv::Mat thresholded__;
00070   };
00071 
00072   class Homography : public Correspondence2d
00073   {
00074   public:
00075     enum { MIN_SIZE = 4 };
00076 
00077     explicit Homography(const T& data) : Correspondence2d(data) {}
00078     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00079     bool ValidData() const
00080     {
00081       return data_.cols == 4 && data_.rows >= MIN_SIZE && data_.type() == CV_32F;
00082     }
00083 
00084   protected:
00085     virtual void CalculateNorms(const M& model, cv::Mat& norms);
00086   };
00087 
00088   class AffineTransform2d : public Correspondence2d
00089   {
00090   public:
00091     enum { MIN_SIZE = 3 };
00092 
00093     explicit AffineTransform2d(const T& data) : Correspondence2d(data) {}
00094     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00095     bool ValidData() const
00096     {
00097       return data_.cols == 4 && data_.rows >= MIN_SIZE && data_.type() == CV_32F;
00098     }
00099   };
00100 
00101   class RigidTransform2d : public Correspondence2d
00102   {
00103   public:
00104     enum { MIN_SIZE = 2 };
00105 
00106     explicit RigidTransform2d(const T& data) : Correspondence2d(data) {}
00107     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00108     bool ValidData() const
00109     {
00110       return data_.cols == 4 && data_.rows >= MIN_SIZE && data_.type() == CV_32F;
00111     }
00112   };
00113 
00114   class Translation2d : public Correspondence2d
00115   {
00116   public:
00117     enum { MIN_SIZE = 1 };
00118 
00119     explicit Translation2d(const T& data) : Correspondence2d(data) {}
00120     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00121     bool ValidData() const
00122     {
00123       return data_.cols == 4 && data_.rows >= MIN_SIZE && data_.type() == CV_32F;
00124     }
00125   };
00126 
00127   bool Valid2dPointCorrespondences(
00128     const cv::Mat& points1,
00129     const cv::Mat& points2);
00130 
00131   bool ZipCorrespondences(
00132     const cv::Mat& points1,
00133     const cv::Mat& points2,
00134     cv::Mat& correspondences);
00135 
00136   template <class Model>
00137   class Fit3d
00138   {
00139   public:
00140     typedef cv::Mat T;         // An Nx3 float matrix
00141     typedef Model M;           // A geometric model
00142 
00143     explicit Fit3d(const T& data) : data_(data) {}
00144 
00145     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const = 0;
00146     int32_t GetInlierCount(const M& model, double max_error)
00147     {
00148       CalculateNorms(model, norms__);
00149 
00150       cv::compare(norms__, cv::Scalar(max_error), thresholded__, cv::CMP_LT);
00151 
00152       return cv::countNonZero(thresholded__);
00153     }
00154 
00155     void GetInliers(const M& model, double max_error, std::vector<uint32_t>& indices)
00156     {
00157       CalculateNorms(model, norms__);
00158 
00159       indices.clear();
00160       indices.reserve(norms__.rows);
00161       double threshold = max_error;
00162       for (int i = 0; i < norms__.rows; i++)
00163       {
00164         if (norms__.at<float>(i) < threshold)
00165         {
00166           indices.push_back(i);
00167         }
00168       }
00169     }
00170 
00171     int32_t Size() const { return data_.rows; }
00172     virtual std::string GetModelString(M& model) const { return ""; }
00173 
00174     static void CopyTo(const M& src, M& dst)
00175     {
00176       src.copyTo(dst);
00177     }
00178 
00179   protected:
00180     virtual void CalculateNorms(const M& model, cv::Mat& norms) = 0;
00181 
00182     const T& data_;
00183 
00184     // Buffer matrices to avoid repeated memory allocations.
00185     cv::Mat norms__;
00186     cv::Mat delta__;
00187     cv::Mat thresholded__;
00188   };
00189 
00190   struct PlaneModel
00191   {
00192     PlaneModel() : x(0), y(0), z(0), i(0), j(0), k(0) {}
00193     void copyTo(PlaneModel& dst) const
00194     {
00195       dst = *this;
00196     }
00197 
00198     float x, y, z, i, j, k;
00199   };
00200 
00201   class PlaneFit : public Fit3d<PlaneModel>
00202   {
00203   public:
00204     enum { MIN_SIZE = 3 };
00205 
00206     PlaneFit(const T& data, float min_angle = 0.2) :
00207         Fit3d<PlaneModel>(data),
00208         min_angle_(min_angle) {}
00209     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00210     bool ValidData() const
00211     {
00212       return data_.cols == 1 && data_.rows >= MIN_SIZE && data_.type() == CV_32FC3;
00213     }
00214 
00215   protected:
00216     virtual void CalculateNorms(const M& model, cv::Mat& norms);
00217 
00218     float min_angle_;
00219   };
00220 
00221   class PerpendicularPlaneWithPointFit : public PlaneFit
00222   {
00223   public:
00224     enum { MIN_SIZE = 2 };
00225 
00226     PerpendicularPlaneWithPointFit(const T& data, 
00227                                    const cv::Vec3f& point_on_plane = cv::Vec3f(0,0,0), 
00228                                    const cv::Vec3f& perp_axis = cv::Vec3f(0,0,1),
00229                                    float max_axis_angle = 0.5, 
00230                                    float min_angle = 0.2) :
00231         PlaneFit(data, min_angle),
00232         point_(point_on_plane),
00233         perp_axis_(perp_axis),
00234         max_axis_angle_(max_axis_angle)
00235     {}
00236 
00237     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00238 
00239   protected:
00240 
00241     cv::Vec3f point_;
00242     cv::Vec3f perp_axis_;
00243     float max_axis_angle_;
00244   };
00245 
00246   struct LineModel3d
00247   {
00248     LineModel3d() : x(0), y(0), z(0), i(0), j(0), k(0) {}
00249     void copyTo(LineModel3d& dst) const
00250     {
00251       dst = *this;
00252     }
00253 
00254     float x, y, z, i, j, k;
00255   };
00256 
00257   class LineFit3d : public Fit3d<LineModel3d>
00258   {
00259   public:
00260     enum { MIN_SIZE = 2 };
00261 
00262     LineFit3d(const T& data) : Fit3d<LineModel3d>(data) {}
00263     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00264     bool ValidData() const
00265     {
00266       return data_.cols == 1 && data_.rows >= MIN_SIZE && data_.type() == CV_32FC3;
00267     }
00268 
00269   protected:
00270     virtual void CalculateNorms(const M& model, cv::Mat& norms);
00271 
00272     cv::Mat temp1__;
00273     cv::Mat temp2__;
00274     cv::Mat x0_p_dot_n__;
00275     cv::Mat x0_p__;
00276   };
00277 
00278   class OrthoLineFit3d : public LineFit3d
00279   {
00280   public:
00281     OrthoLineFit3d(const T& data, const LineModel3d& ortho, float angle_tolerance = 0.09) : 
00282       LineFit3d(data), ortho_(ortho), angle_tolerance_(angle_tolerance) {}
00283     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00284 
00285   protected:
00286     LineModel3d ortho_;
00287     float angle_tolerance_;
00288   };
00289 
00290   struct CrossModel3d
00291   {
00292     CrossModel3d() : x(0), y(0), z(0), i1(0), j1(0), k1(0), i2(0), j2(0), k2(0) {}
00293     void copyTo(CrossModel3d& dst) const
00294     {
00295       dst = *this;
00296     }
00297 
00298     float x, y, z, i1, j1, k1, i2, j2, k2;
00299   };
00300 
00301   class CrossFit3d : public Fit3d<CrossModel3d>
00302   {
00303   public:
00304     enum { MIN_SIZE = 3 };
00305 
00306     CrossFit3d(const T& data, float min_angle = 0.2) :
00307         Fit3d<CrossModel3d>(data),
00308         min_angle_(min_angle) {}
00309     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00310     bool ValidData() const
00311     {
00312       return data_.cols == 1 && data_.rows >= MIN_SIZE && data_.type() == CV_32FC3;
00313     }
00314 
00315   protected:
00316     virtual void CalculateNorms(const M& model, cv::Mat& norms);
00317 
00318     float min_angle_;
00319     cv::Mat temp1__;
00320     cv::Mat temp2__;
00321     cv::Mat temp3__;
00322     cv::Mat x0_p_dot_n__;
00323     cv::Mat x0_p__;
00324   };
00325 
00326 }
00327 
00328 #endif  // OPENCV_UTIL_MODELS_H_


swri_opencv_util
Author(s): Marc Alban
autogenerated on Tue Oct 3 2017 03:19:24