model_fit.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_MODEL_FIT_H_
00031 #define OPENCV_UTIL_MODEL_FIT_H_
00032 
00033 #include <vector>
00034 
00035 #include <opencv2/core/core.hpp>
00036 
00037 #include <swri_math_util/random.h>
00038 #include <swri_math_util/ransac.h>
00039 
00040 #include <swri_opencv_util/models.h>
00041 
00042 namespace swri_opencv_util
00043 {
00044   template <class Model>
00045   cv::Mat FindModel2d(
00046     const cv::Mat& points1,
00047     const cv::Mat& points2,
00048     cv::Mat& inliers1,
00049     cv::Mat& inliers2,
00050     std::vector<uint32_t> &good_points,
00051     int32_t& iterations,
00052     double max_error = 1.0,
00053     double confidence = 0.9,
00054     int32_t max_iterations = 1000,
00055     swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr())
00056   {
00057     cv::Mat model;
00058 
00059     // Put data into the expected format.
00060     cv::Mat correspondences;
00061     if (!ZipCorrespondences(points1, points2, correspondences))
00062     {
00063       return model;
00064     }
00065 
00066     // Run RANSAC to robustly fit a rigid transform model to the set of
00067     // corresponding points.
00068     swri_math_util::Ransac<Model> ransac(rng);
00069 
00070     Model fit_model(correspondences);
00071     model = ransac.FitModel(
00072       fit_model, max_error, confidence, 1, max_iterations, good_points, iterations);
00073 
00074     if (good_points.empty())
00075     {
00076       return model;
00077     }
00078 
00079     // Populate output data.
00080     bool row_order = points1.rows > 1;
00081     if (row_order)
00082     {
00083       inliers1 = cv::Mat(good_points.size(), 1, CV_32FC2);
00084       inliers2 = cv::Mat(good_points.size(), 1, CV_32FC2);
00085       for (size_t i = 0; i < good_points.size(); ++i)
00086       {
00087         inliers1.at<cv::Vec2f>(i, 0) = points1.at<cv::Vec2f>(good_points[i], 0);
00088         inliers2.at<cv::Vec2f>(i, 0) = points2.at<cv::Vec2f>(good_points[i], 0);
00089       }
00090     }
00091     else
00092     {
00093       inliers1 = cv::Mat(1, good_points.size(), CV_32FC2);
00094       inliers2 = cv::Mat(1, good_points.size(), CV_32FC2);
00095       for (size_t i = 0; i < good_points.size(); ++i)
00096       {
00097         inliers1.at<cv::Vec2f>(0, i) = points1.at<cv::Vec2f>(0, good_points[i]);
00098         inliers2.at<cv::Vec2f>(0, i) = points2.at<cv::Vec2f>(0, good_points[i]);
00099       }
00100     }
00101 
00102     return model;
00103   }
00104 
00105   cv::Mat FindTranslation2d(
00106     const cv::Mat& points1,
00107     const cv::Mat& points2,
00108     cv::Mat& inliers1,
00109     cv::Mat& inliers2,
00110     std::vector<uint32_t> &good_points,
00111     int32_t& iterations,
00112     double max_error = 1.0,
00113     double confidence = 0.9,
00114     int32_t max_iterations = 1000,
00115     swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00116 
00117   cv::Mat FindRigidTransform2d(
00118     const cv::Mat& points1,
00119     const cv::Mat& points2,
00120     cv::Mat& inliers1,
00121     cv::Mat& inliers2,
00122     std::vector<uint32_t> &good_points,
00123     int32_t& iterations,
00124     double max_error = 1.0,
00125     double confidence = 0.9,
00126     int32_t max_iterations = 1000,
00127     swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00128 
00129   // Returns a 2x3 transform that can be applied to points1 to align them to points2.
00130   cv::Mat FitRigidTransform2d(const cv::Mat& points1, const cv::Mat& points2);
00131 
00132   cv::Mat FindAffineTransform2d(
00133     const cv::Mat& points1,
00134     const cv::Mat& points2,
00135     cv::Mat& inliers1,
00136     cv::Mat& inliers2,
00137     std::vector<uint32_t> &good_points,
00138     int32_t& iterations,
00139     double max_error = 1.0,
00140     double confidence = 0.9,
00141     int32_t max_iterations = 1000,
00142     swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00143 
00144   cv::Mat FitAffineTransform2d(const cv::Mat& points1, const cv::Mat& points2);
00145 
00146   cv::Mat FindHomography(
00147     const cv::Mat& points1,
00148     const cv::Mat& points2,
00149     cv::Mat& inliers1,
00150     cv::Mat& inliers2,
00151     std::vector<uint32_t> &good_points,
00152     int32_t& iterations,
00153     double max_error = 1.0,
00154     double confidence = 0.9,
00155     int32_t max_iterations = 1000,
00156     swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00157 
00158   PlaneModel FindPerpendicularPlaneWithPoint(
00159     const cv::Vec3f& point_on_plane,
00160     const cv::Vec3f& perp_axis,
00161     double max_angle_from_perp,
00162     const cv::Mat& points,
00163     cv::Mat& inliers,
00164     std::vector<uint32_t> &good_points,
00165     int32_t& iterations,
00166     double max_error,
00167     double confidence,
00168     int32_t min_iterations,
00169     int32_t max_iterations,
00170     swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00171 
00172   PlaneModel FindPlane(
00173     const cv::Mat& points,
00174     cv::Mat& inliers,
00175     std::vector<uint32_t> &good_points,
00176     int32_t& iterations,
00177     double max_error = 1.0,
00178     double confidence = 0.9,
00179     int32_t min_iterations = 1,
00180     int32_t max_iterations = 1000,
00181     swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00182 
00183   PlaneModel FitPlane(const cv::Mat& points);
00184 
00185   LineModel3d FindLine3d(
00186     const cv::Mat& points,
00187     cv::Mat& inliers,
00188     std::vector<uint32_t> &good_points,
00189     int32_t& iterations,
00190     double max_error = 1.0,
00191     double confidence = 0.9,
00192     int32_t min_iterations = 1,
00193     int32_t max_iterations = 1000,
00194     swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00195 
00196   LineModel3d FindOrthoLine3d(
00197     const cv::Mat& points,
00198     const LineModel3d& ortho,
00199     cv::Mat& inliers,
00200     std::vector<uint32_t> &good_points,
00201     int32_t& iterations,
00202     double max_error = 1.0,
00203     double confidence = 0.9,
00204     int32_t min_iterations = 1,
00205     int32_t max_iterations = 1000,
00206     swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00207 
00208   LineModel3d FitLine3d(const cv::Mat& points);
00209 
00210   CrossModel3d FindCross3d(
00211     const cv::Mat& points,
00212     cv::Mat& inliers,
00213     std::vector<uint32_t> &good_points,
00214     int32_t& iterations,
00215     double max_error = 1.0,
00216     double confidence = 0.9,
00217     int32_t min_iterations = 1,
00218     int32_t max_iterations = 1000,
00219     swri_math_util::RandomGeneratorPtr rng = swri_math_util::RandomGeneratorPtr());
00220 }
00221 
00222 #endif  // OPENCV_UTIL_MODEL_FIT_H_


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