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 Valid3dPointCorrespondences(
00132     const cv::Mat& points1,
00133     const cv::Mat& points2);
00134 
00135   bool ZipCorrespondences(
00136     const cv::Mat& points1,
00137     const cv::Mat& points2,
00138     cv::Mat& correspondences);
00139 
00140   template <class Model>
00141   class Fit3d
00142   {
00143   public:
00144     typedef cv::Mat T;         // An Nx3 float matrix
00145     typedef Model M;           // A geometric model
00146 
00147     explicit Fit3d(const T& data) : data_(data) {}
00148 
00149     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const = 0;
00150     int32_t GetInlierCount(const M& model, double max_error)
00151     {
00152       CalculateNorms(model, norms__);
00153 
00154       cv::compare(norms__, cv::Scalar(max_error), thresholded__, cv::CMP_LT);
00155 
00156       return cv::countNonZero(thresholded__);
00157     }
00158 
00159     void GetInliers(const M& model, double max_error, std::vector<uint32_t>& indices)
00160     {
00161       CalculateNorms(model, norms__);
00162 
00163       indices.clear();
00164       indices.reserve(norms__.rows);
00165       double threshold = max_error;
00166       for (int i = 0; i < norms__.rows; i++)
00167       {
00168         if (norms__.at<float>(i) < threshold)
00169         {
00170           indices.push_back(i);
00171         }
00172       }
00173     }
00174 
00175     int32_t Size() const { return data_.rows; }
00176     virtual std::string GetModelString(M& model) const { return ""; }
00177 
00178     static void CopyTo(const M& src, M& dst)
00179     {
00180       src.copyTo(dst);
00181     }
00182 
00183   protected:
00184     virtual void CalculateNorms(const M& model, cv::Mat& norms) = 0;
00185 
00186     const T& data_;
00187 
00188     // Buffer matrices to avoid repeated memory allocations.
00189     cv::Mat norms__;
00190     cv::Mat delta__;
00191     cv::Mat thresholded__;
00192   };
00193 
00194   struct PlaneModel
00195   {
00196     PlaneModel() : x(0), y(0), z(0), i(0), j(0), k(0) {}
00197     void copyTo(PlaneModel& dst) const
00198     {
00199       dst = *this;
00200     }
00201 
00202     float x, y, z, i, j, k;
00203   };
00204 
00205   class PlaneFit : public Fit3d<PlaneModel>
00206   {
00207   public:
00208     enum { MIN_SIZE = 3 };
00209 
00210     PlaneFit(const T& data, float min_angle = 0.2) :
00211         Fit3d<PlaneModel>(data),
00212         min_angle_(min_angle) {}
00213     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00214     bool ValidData() const
00215     {
00216       return data_.cols == 1 && data_.rows >= MIN_SIZE && data_.type() == CV_32FC3;
00217     }
00218 
00219   protected:
00220     virtual void CalculateNorms(const M& model, cv::Mat& norms);
00221 
00222     float min_angle_;
00223   };
00224 
00225   class PerpendicularPlaneWithPointFit : public PlaneFit
00226   {
00227   public:
00228     enum { MIN_SIZE = 2 };
00229 
00230     PerpendicularPlaneWithPointFit(const T& data,
00231                                    const cv::Vec3f& point_on_plane = cv::Vec3f(0,0,0),
00232                                    const cv::Vec3f& perp_axis = cv::Vec3f(0,0,1),
00233                                    float max_axis_angle = 0.5,
00234                                    float min_angle = 0.2) :
00235         PlaneFit(data, min_angle),
00236         point_(point_on_plane),
00237         perp_axis_(perp_axis),
00238         max_axis_angle_(max_axis_angle)
00239     {}
00240 
00241     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00242 
00243   protected:
00244 
00245     cv::Vec3f point_;
00246     cv::Vec3f perp_axis_;
00247     float max_axis_angle_;
00248   };
00249 
00250   struct LineModel3d
00251   {
00252     LineModel3d() : x(0), y(0), z(0), i(0), j(0), k(0) {}
00253     void copyTo(LineModel3d& dst) const
00254     {
00255       dst = *this;
00256     }
00257 
00258     float x, y, z, i, j, k;
00259   };
00260 
00261   class LineFit3d : public Fit3d<LineModel3d>
00262   {
00263   public:
00264     enum { MIN_SIZE = 2 };
00265 
00266     LineFit3d(const T& data) : Fit3d<LineModel3d>(data) {}
00267     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00268     bool ValidData() const
00269     {
00270       return data_.cols == 1 && data_.rows >= MIN_SIZE && data_.type() == CV_32FC3;
00271     }
00272 
00273   protected:
00274     virtual void CalculateNorms(const M& model, cv::Mat& norms);
00275 
00276     cv::Mat temp1__;
00277     cv::Mat temp2__;
00278     cv::Mat x0_p_dot_n__;
00279     cv::Mat x0_p__;
00280   };
00281 
00282   class OrthoLineFit3d : public LineFit3d
00283   {
00284   public:
00285     OrthoLineFit3d(const T& data, const LineModel3d& ortho, float angle_tolerance = 0.09) :
00286       LineFit3d(data), ortho_(ortho), angle_tolerance_(angle_tolerance) {}
00287     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00288 
00289   protected:
00290     LineModel3d ortho_;
00291     float angle_tolerance_;
00292   };
00293 
00294   struct CrossModel3d
00295   {
00296     CrossModel3d() : x(0), y(0), z(0), i1(0), j1(0), k1(0), i2(0), j2(0), k2(0) {}
00297     void copyTo(CrossModel3d& dst) const
00298     {
00299       dst = *this;
00300     }
00301 
00302     float x, y, z, i1, j1, k1, i2, j2, k2;
00303   };
00304 
00305   class CrossFit3d : public Fit3d<CrossModel3d>
00306   {
00307   public:
00308     enum { MIN_SIZE = 3 };
00309 
00310     CrossFit3d(const T& data, float min_angle = 0.2) :
00311         Fit3d<CrossModel3d>(data),
00312         min_angle_(min_angle) {}
00313     virtual bool GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const;
00314     bool ValidData() const
00315     {
00316       return data_.cols == 1 && data_.rows >= MIN_SIZE && data_.type() == CV_32FC3;
00317     }
00318 
00319   protected:
00320     virtual void CalculateNorms(const M& model, cv::Mat& norms);
00321 
00322     float min_angle_;
00323     cv::Mat temp1__;
00324     cv::Mat temp2__;
00325     cv::Mat temp3__;
00326     cv::Mat x0_p_dot_n__;
00327     cv::Mat x0_p__;
00328   };
00329 
00330 }
00331 
00332 #endif  // OPENCV_UTIL_MODELS_H_


swri_opencv_util
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 20:34:45