models.cpp
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 #include <swri_opencv_util/models.h>
00031 
00032 #include <opencv2/imgproc/imgproc.hpp>
00033 
00034 namespace swri_opencv_util
00035 {
00036 
00037   int32_t Correspondence2d::GetInlierCount(const M& model, double max_error)
00038   {
00039     CalculateNorms(model, norms__);
00040 
00041     cv::compare(norms__, cv::Scalar(max_error * max_error), thresholded__, cv::CMP_LT);
00042 
00043     return cv::countNonZero(thresholded__);
00044   }
00045 
00046   void Correspondence2d::GetInliers(const M& model, double max_error, std::vector<uint32_t>& indices)
00047   {
00048     CalculateNorms(model, norms__);
00049 
00050     indices.clear();
00051     indices.reserve(norms__.rows);
00052     double threshold = max_error * max_error;
00053     for (int i = 0; i < norms__.rows; i++)
00054     {
00055       if (norms__.at<float>(i) < threshold)
00056       {
00057         indices.push_back(i);
00058       }
00059     }
00060   }
00061 
00062   void Correspondence2d::CalculateNorms(const M& model, cv::Mat& norms)
00063   {
00064     cv::Mat src = data_(cv::Rect(0, 0, 2, data_.rows)).reshape(2);
00065     cv::transform(src, predicted__, model);
00066     cv::Mat measured = data_(cv::Rect(2, 0, 2, data_.rows));
00067     cv::subtract(predicted__.reshape(1), measured, delta__);
00068     cv::multiply(delta__, delta__, delta_squared__);
00069     cv::add(
00070       delta_squared__(cv::Rect(0, 0, 1, delta__.rows)),
00071       delta_squared__(cv::Rect(1, 0, 1, delta__.rows)),
00072       norms);
00073   }
00074 
00075   bool Homography::GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const
00076   {
00077     if (indices.size() != MIN_SIZE)
00078     {
00079       return false;
00080     }
00081 
00082     cv::Mat src(MIN_SIZE, 1, CV_32FC2);
00083     cv::Mat dst(MIN_SIZE, 1, CV_32FC2);
00084 
00085     for (int32_t i = 0; i < MIN_SIZE; i++)
00086     {
00087       const float* sample = data_.ptr<float>(indices[i]);
00088       src.at<cv::Vec2f>(i, 0) = cv::Vec2f(sample[0], sample[1]);
00089       dst.at<cv::Vec2f>(i, 0) = cv::Vec2f(sample[2], sample[3]);
00090     }
00091 
00092     model = cv::getPerspectiveTransform(src, dst);
00093 
00094     // Test input points for if they all match the generated model.
00095     cv::Mat predicted;
00096     cv::perspectiveTransform(src, predicted, model);
00097     cv::Mat delta, delta_squared, norms;
00098     cv::subtract(predicted.reshape(1), dst.reshape(1), delta);
00099     cv::multiply(delta, delta, delta_squared);
00100     cv::add(
00101       delta_squared(cv::Rect(0, 0, 1, delta.rows)),
00102       delta_squared(cv::Rect(1, 0, 1, delta.rows)),
00103       norms);
00104 
00105     double min, max;
00106     cv::minMaxLoc(norms, &min, &max);
00107 
00108     return max < max_error * max_error;
00109   }
00110 
00111   void Homography::CalculateNorms(const M& model, cv::Mat& norms)
00112   {
00113     cv::Mat src = data_(cv::Rect(0, 0, 2, data_.rows)).reshape(2);
00114     cv::perspectiveTransform(src, predicted__, model);
00115     cv::Mat measured = data_(cv::Rect(2, 0, 2, data_.rows));
00116     cv::subtract(predicted__.reshape(1), measured, delta__);
00117     cv::multiply(delta__, delta__, delta_squared__);
00118     cv::add(
00119       delta_squared__(cv::Rect(0, 0, 1, delta__.rows)),
00120       delta_squared__(cv::Rect(1, 0, 1, delta__.rows)),
00121       norms);
00122   }
00123 
00124   bool AffineTransform2d::GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const
00125   {
00126     if (indices.size() != MIN_SIZE)
00127     {
00128       return false;
00129     }
00130 
00131     cv::Mat src(MIN_SIZE, 1, CV_32FC2);
00132     cv::Mat dst(MIN_SIZE, 1, CV_32FC2);
00133 
00134     for (int32_t i = 0; i < MIN_SIZE; i++)
00135     {
00136       const float* sample = data_.ptr<float>(indices[i]);
00137       src.at<cv::Vec2f>(i, 0) = cv::Vec2f(sample[0], sample[1]);
00138       dst.at<cv::Vec2f>(i, 0) = cv::Vec2f(sample[2], sample[3]);
00139     }
00140 
00141     model = cv::getAffineTransform(src, dst);
00142 
00143     // Test input points for if they all match the generated model.
00144     cv::Mat predicted;
00145     cv::transform(src, predicted, model);
00146     cv::Mat delta, delta_squared, norms;
00147     cv::subtract(predicted.reshape(1), dst.reshape(1), delta);
00148     cv::multiply(delta, delta, delta_squared);
00149     cv::add(
00150       delta_squared(cv::Rect(0, 0, 1, delta.rows)),
00151       delta_squared(cv::Rect(1, 0, 1, delta.rows)),
00152       norms);
00153 
00154     double min, max;
00155     cv::minMaxLoc(norms, &min, &max);
00156 
00157     return max < max_error * max_error;
00158   }
00159 
00160   bool RigidTransform2d::GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const
00161   {
00162     if (indices.size() != MIN_SIZE)
00163     {
00164       return false;
00165     }
00166 
00167     cv::Point2f src[MIN_SIZE];
00168     cv::Point2f dst[MIN_SIZE];
00169 
00170     for (int32_t i = 0; i < MIN_SIZE; i++)
00171     {
00172       const float* sample = data_.ptr<float>(indices[i]);
00173       src[i].x = sample[0];
00174       src[i].y = sample[1];
00175       dst[i].x = sample[2];
00176       dst[i].y = sample[3];
00177     }
00178 
00179     double len_src = cv::norm(src[1] - src[0]);
00180     double len_dst = cv::norm(dst[1] - dst[0]);
00181     if (std::fabs(len_src - len_dst) >= max_error)
00182     {
00183       return false;
00184     }
00185 
00186     // Construct a x-axis for both sets.
00187     cv::Point2f src_x = (src[1] - src[0]) * (1.0 / len_src);
00188     cv::Point2f dst_x = (dst[1] - dst[0]) * (1.0 / len_dst);
00189 
00190     // Construct a y-axis for both sets.
00191     cv::Point2f src_y(src_x.y, -src_x.x);
00192     src_y *= 1.0 / cv::norm(src_y);
00193 
00194     cv::Point2f dst_y(dst_x.y, -dst_x.x);
00195     dst_y *= 1.0 / cv::norm(dst_y);
00196 
00197     // Build rotation matrices for both sets.
00198     cv::Mat src_r(2, 2, CV_32F);
00199     src_r.at<float>(0, 0) = src_x.x;
00200     src_r.at<float>(1, 0) = src_x.y;
00201     src_r.at<float>(0, 1) = src_y.x;
00202     src_r.at<float>(1, 1) = src_y.y;
00203 
00204     cv::Mat dst_r(2, 2, CV_32F);
00205     dst_r.at<float>(0, 0) = dst_x.x;
00206     dst_r.at<float>(1, 0) = dst_x.y;
00207     dst_r.at<float>(0, 1) = dst_y.x;
00208     dst_r.at<float>(1, 1) = dst_y.y;
00209 
00210     // Solve for the rotation between src and dst
00211     //    R R_src = R_dst
00212     //    R = R_dst R_src^T
00213     cv::Mat rotation = dst_r * src_r.t();
00214 
00215     // Calculate the translation between src (rotated) and dst.
00216     cv::Mat src0_rotated(2, 1, CV_32F);
00217     src0_rotated.at<float>(0, 0) = src[0].x;
00218     src0_rotated.at<float>(1, 0) = src[0].y;
00219     src0_rotated = rotation * src0_rotated;
00220     float t_x = dst[0].x - src0_rotated.at<float>(0, 0);
00221     float t_y = dst[0].y - src0_rotated.at<float>(1, 0);
00222 
00223     model.create(2, 3, CV_32F);
00224     model.at<float>(0, 0) = rotation.at<float>(0, 0);
00225     model.at<float>(0, 1) = rotation.at<float>(0, 1);
00226     model.at<float>(1, 0) = rotation.at<float>(1, 0);
00227     model.at<float>(1, 1) = rotation.at<float>(1, 1);
00228     model.at<float>(0, 2) = t_x;
00229     model.at<float>(1, 2) = t_y;
00230 
00231     return true;
00232   }
00233 
00234   bool Translation2d::GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const
00235   {
00236     if (indices.size() != MIN_SIZE)
00237     {
00238       return false;
00239     }
00240 
00241     cv::Point2f src;
00242     cv::Point2f dst;
00243 
00244     const float* sample = data_.ptr<float>(indices[0]);
00245     src.x = sample[0];
00246     src.y = sample[1];
00247     dst.x = sample[2];
00248     dst.y = sample[3];
00249 
00250     // Calculate the translation between src (rotated) and dst.
00251     float t_x = dst.x - src.x;
00252     float t_y = dst.y - src.y;
00253 
00254     model.create(2, 3, CV_32F);
00255     model.at<float>(0, 0) = 1.0f;
00256     model.at<float>(0, 1) = 0.0f;
00257     model.at<float>(1, 0) = 0.0f;
00258     model.at<float>(1, 1) = 1.0f;
00259     model.at<float>(0, 2) = t_x;
00260     model.at<float>(1, 2) = t_y;
00261 
00262     return true;
00263   }
00264 
00265   bool Valid2dPointCorrespondences(
00266     const cv::Mat& points1,
00267     const cv::Mat& points2)
00268   {
00269     if (points1.type() != points2.type())
00270     {
00271       return false;
00272     }
00273 
00274     if (points1.type() != CV_32FC2)
00275     {
00276       return false;
00277     }
00278 
00279     if (points1.cols != points2.cols  || points1.rows  != points2.rows)
00280     {
00281       return false;
00282     }
00283 
00284     if (points1.cols != 1 && points1.rows != 1)
00285     {
00286       return false;
00287     }
00288 
00289     return true;
00290   }
00291 
00292   bool Valid3dPointCorrespondences(
00293     const cv::Mat& points1,
00294     const cv::Mat& points2)
00295   {
00296     if (points1.type() != points2.type())
00297     {
00298       return false;
00299     }
00300 
00301     if (points1.type() != CV_32FC3)
00302     {
00303       return false;
00304     }
00305 
00306     if (points1.cols != points2.cols  || points1.rows  != points2.rows)
00307     {
00308       return false;
00309     }
00310 
00311     if (points1.cols != 1)
00312     {
00313       return false;
00314     }
00315 
00316     return true;
00317   }
00318 
00319   bool ZipCorrespondences(
00320     const cv::Mat& points1,
00321     const cv::Mat& points2,
00322     cv::Mat& correspondeces)
00323   {
00324     if (!Valid2dPointCorrespondences(points1, points2))
00325     {
00326       return false;
00327     }
00328 
00329     size_t num_points = points1.cols;
00330     bool row_order = false;
00331     if (points1.rows > 1)
00332     {
00333       row_order = true;
00334       num_points = points1.rows;
00335     }
00336 
00337     // Put data into the correct format.
00338     if (row_order)
00339     {
00340       cv::hconcat(points1.reshape(1), points2.reshape(1), correspondeces);
00341     }
00342     else
00343     {
00344       cv::hconcat(
00345         points1.reshape(0, num_points).reshape(1),
00346         points2.reshape(0, num_points).reshape(1),
00347         correspondeces);
00348     }
00349 
00350     return true;
00351   }
00352 
00353 
00354   bool PerpendicularPlaneWithPointFit::GetModel(const std::vector<int32_t>& indices, M& model,
00355                                                 double max_error) const
00356   {
00357     if (indices.size() != MIN_SIZE)
00358     {
00359       return false;
00360     }
00361 
00362     // Check if points are collinear.
00363 
00364     cv::Mat points = data_.reshape(3);
00365 
00366     cv::Vec3f p1 = points.at<cv::Vec3f>(indices[0], 0);
00367     cv::Vec3f p2 = points.at<cv::Vec3f>(indices[1], 0);
00368     cv::Vec3f p3 = point_;
00369 
00370     cv::Point3f v12 = p2 - p1;
00371     cv::Point3f v13 = p3 - p1;
00372     float d12 = cv::norm(v12);
00373     float d13 = cv::norm(v13);
00374     float d = std::fabs(d12 * d13);
00375     if (d == 0)
00376     {
00377       return false;
00378     }
00379 
00380     float angle = std::acos(v12.dot(v13) / d);
00381     if (angle < min_angle_ || angle + min_angle_ > M_PI)
00382     {
00383       return false;
00384     }
00385 
00386     // Calculate model.
00387 
00388     cv::Vec3f normal = v12.cross(v13);
00389     normal = normal / cv::norm(normal);
00390 
00391     if (std::acos(normal.dot(perp_axis_)) > max_axis_angle_)
00392     {
00393       return false;
00394     }
00395 
00396     model.x = p1[0];
00397     model.y = p1[1];
00398     model.z = p1[2];
00399     model.i = normal[0];
00400     model.j = normal[1];
00401     model.k = normal[2];
00402 
00403     return true;
00404   }
00405 
00406   bool PlaneFit::GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const
00407   {
00408     if (indices.size() != MIN_SIZE)
00409     {
00410       return false;
00411     }
00412 
00413     // Check if points are collinear.
00414 
00415     cv::Mat points = data_.reshape(3);
00416 
00417     cv::Vec3f p1 = points.at<cv::Vec3f>(indices[0], 0);
00418     cv::Vec3f p2 = points.at<cv::Vec3f>(indices[1], 0);
00419     cv::Vec3f p3 = points.at<cv::Vec3f>(indices[2], 0);
00420 
00421     cv::Point3f v12 = p2 - p1;
00422     cv::Point3f v13 = p3 - p1;
00423     float d12 = cv::norm(v12);
00424     float d13 = cv::norm(v13);
00425     float d = std::fabs(d12 * d13);
00426     if (d == 0)
00427     {
00428       return false;
00429     }
00430 
00431     float angle = std::acos(v12.dot(v13) / d);
00432     if (angle < min_angle_ || angle + min_angle_ > M_PI)
00433     {
00434       return false;
00435     }
00436 
00437     // Calculate model.
00438 
00439     cv::Vec3f normal = v12.cross(v13);
00440     normal = normal / cv::norm(normal);
00441 
00442     model.x = p1[0];
00443     model.y = p1[1];
00444     model.z = p1[2];
00445     model.i = normal[0];
00446     model.j = normal[1];
00447     model.k = normal[2];
00448 
00449     return true;
00450   }
00451 
00452   void PlaneFit::CalculateNorms(const M& model, cv::Mat& norms)
00453   {
00454     // Subtract the origin point of the plane from each data point
00455     cv::Mat single_column = data_.reshape(3);
00456     cv::subtract(single_column, cv::Scalar(model.x, model.y, model.z), delta__);
00457 
00458     // Calculate the dot product of each adjusted data point with the normal
00459     // of the plane.
00460     cv::Mat split_columns = delta__.reshape(1);
00461     cv::Mat x = split_columns(cv::Rect(0, 0, 1, split_columns.rows));
00462     cv::Mat y = split_columns(cv::Rect(1, 0, 1, split_columns.rows));
00463     cv::Mat z = split_columns(cv::Rect(2, 0, 1, split_columns.rows));
00464     x = x * model.i;
00465     y = y * model.j;
00466     z = z * model.k;
00467     cv::add(x, y, norms);
00468     cv::add(norms, z, norms);
00469     norms = cv::abs(norms);
00470   }
00471 
00472   bool LineFit3d::GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const
00473   {
00474     if (indices.size() != MIN_SIZE)
00475     {
00476       return false;
00477     }
00478 
00479     cv::Mat points = data_.reshape(3);
00480 
00481     cv::Point3f p1(points.at<cv::Vec3f>(indices[0], 0));
00482     cv::Point3f p2(points.at<cv::Vec3f>(indices[1], 0));
00483 
00484     cv::Point3f v12 = p2 - p1;
00485     v12 = cv::Vec3f(v12) / cv::norm(v12);
00486 
00487     model.x = p1.x;
00488     model.y = p1.y;
00489     model.z = p1.z;
00490     model.i = v12.x;
00491     model.j = v12.y;
00492     model.k = v12.z;
00493 
00494     return true;
00495   }
00496 
00497   void LineFit3d::CalculateNorms(const M& model, cv::Mat& norms)
00498   {
00499     // d = ||(x0 - p) - ((x0 - p) . n)n||
00500 
00501     cv::Scalar x0(model.x, model.y, model.z);
00502     cv::Scalar n(model.i, model.j, model.k);
00503     cv::Mat p = data_.reshape(3);
00504 
00505     if (temp1__.size != p.size)
00506     {
00507       temp1__ = cv::Mat(p.rows, p.cols, p.type());
00508     }
00509     temp1__.setTo(n);
00510     cv::Mat n_columns = temp1__.reshape(1);
00511     cv::Mat n_x = n_columns(cv::Rect(0, 0, 1, n_columns.rows));
00512     cv::Mat n_y = n_columns(cv::Rect(1, 0, 1, n_columns.rows));
00513     cv::Mat n_z = n_columns(cv::Rect(2, 0, 1, n_columns.rows));
00514 
00515     // (x0 - p)
00516     cv::subtract(p, x0, x0_p__);
00517 
00518     // (x0 - p) . n
00519     cv::multiply(x0_p__, temp1__, temp2__);
00520     cv::reduce(temp2__.reshape(1), x0_p_dot_n__, 1, CV_REDUCE_SUM);
00521 
00522     // ((x0 - p) . n)n
00523     cv::multiply(n_x, x0_p_dot_n__, n_x);
00524     cv::multiply(n_y, x0_p_dot_n__, n_y);
00525     cv::multiply(n_z, x0_p_dot_n__, n_z);
00526 
00527     // (x0 - p) - ((x0 - p) . n)n
00528     cv::subtract(x0_p__, temp1__, temp1__);
00529 
00530     // d = ||(x0 - p) - ((x0 - p) . n)n||
00531     cv::multiply(n_x, n_x, n_x);
00532     cv::multiply(n_y, n_y, n_y);
00533     cv::multiply(n_z, n_z, n_z);
00534     cv::reduce(temp1__.reshape(1), norms, 1, CV_REDUCE_SUM);
00535     cv::sqrt(norms, norms);
00536   }
00537 
00538   bool OrthoLineFit3d::GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const
00539   {
00540     if (indices.size() != MIN_SIZE)
00541     {
00542       return false;
00543     }
00544 
00545     cv::Mat points = data_.reshape(3);
00546 
00547     cv::Point3f p1(points.at<cv::Vec3f>(indices[0], 0));
00548     cv::Point3f p2(points.at<cv::Vec3f>(indices[1], 0));
00549 
00550     cv::Point3f v12 = p2 - p1;
00551     v12 = cv::Vec3f(v12) / cv::norm(v12);
00552 
00553     // Check if orthogonal
00554     cv::Point3f ortho(ortho_.i, ortho_.j, ortho_.k);
00555     ortho = cv::Vec3f(ortho) / cv::norm(ortho);
00556 
00557     float angle = std::acos(v12.dot(ortho));
00558     float error = std::fabs(M_PI * 0.5 - angle);
00559     if (error > angle_tolerance_)
00560     {
00561       return false;
00562     }
00563 
00564     model.x = p1.x;
00565     model.y = p1.y;
00566     model.z = p1.z;
00567     model.i = v12.x;
00568     model.j = v12.y;
00569     model.k = v12.z;
00570 
00571     return true;
00572   }
00573 
00574   bool CrossFit3d::GetModel(const std::vector<int32_t>& indices, M& model, double max_error) const
00575   {
00576     if (indices.size() != MIN_SIZE)
00577     {
00578       return false;
00579     }
00580 
00581     // Check if points are collinear.
00582 
00583     cv::Mat points = data_.reshape(3);
00584 
00585     cv::Point3f p1(points.at<cv::Vec3f>(indices[0], 0));
00586     cv::Point3f p2(points.at<cv::Vec3f>(indices[1], 0));
00587     cv::Point3f p3(points.at<cv::Vec3f>(indices[2], 0));
00588 
00589     cv::Point3f v12 = p2 - p1;
00590     cv::Point3f v13 = p3 - p1;
00591     float d12 = cv::norm(v12);
00592     float d13 = cv::norm(v13);
00593     float d = std::fabs(d12 * d13);
00594     if (d == 0)
00595     {
00596       return false;
00597     }
00598 
00599     float angle = std::acos(v12.dot(v13) / d);
00600     if (angle < min_angle_ || angle + min_angle_ > M_PI)
00601     {
00602       return false;
00603     }
00604 
00605     // Calculate model.
00606 
00607     // Orthogonally project 3rd point onto first line to
00608     // get line through 3rd point orthogonal to the first
00609     // line.
00610     cv::Point3f p4 = p1 + (v13.dot(v12) / v12.dot(v12)) * v12;
00611     cv::Point3f v34 = p4 - p3;
00612 
00613     // Get unit vector of the lines.
00614     v12 = cv::Vec3f(v12) / cv::norm(v12);
00615     v34 = cv::Vec3f(v34) / cv::norm(v34);
00616 
00617     model.x = p4.x;
00618     model.y = p4.y;
00619     model.z = p4.z;
00620     model.i1 = v12.x;
00621     model.j1 = v12.y;
00622     model.k1 = v12.z;
00623     model.i2 = v34.x;
00624     model.j2 = v34.y;
00625     model.k2 = v34.z;
00626 
00627     return true;
00628   }
00629 
00630   void CrossFit3d::CalculateNorms(const M& model, cv::Mat& norms)
00631   {
00633     // Line 1
00635 
00636     // d = ||(x0 - p) - ((x0 - p) . n)n||
00637 
00638     cv::Scalar x0(model.x, model.y, model.z);
00639     cv::Scalar n(model.i1, model.j1, model.k1);
00640     cv::Mat p = data_.reshape(3);
00641 
00642     if (temp1__.size != p.size)
00643     {
00644       temp1__ = cv::Mat(p.rows, p.cols, p.type());
00645     }
00646     temp1__.setTo(n);
00647     cv::Mat n_columns = temp1__.reshape(1);
00648     cv::Mat n_x = n_columns(cv::Rect(0, 0, 1, n_columns.rows));
00649     cv::Mat n_y = n_columns(cv::Rect(1, 0, 1, n_columns.rows));
00650     cv::Mat n_z = n_columns(cv::Rect(2, 0, 1, n_columns.rows));
00651 
00652     // (x0 - p)
00653     cv::subtract(p, x0, x0_p__);
00654 
00655     // (x0 - p) . n
00656     cv::multiply(x0_p__, temp1__, temp2__);
00657     cv::reduce(temp2__.reshape(1), x0_p_dot_n__, 1, CV_REDUCE_SUM);
00658 
00659     // ((x0 - p) . n)n
00660     cv::multiply(n_x, x0_p_dot_n__, n_x);
00661     cv::multiply(n_y, x0_p_dot_n__, n_y);
00662     cv::multiply(n_z, x0_p_dot_n__, n_z);
00663 
00664     // (x0 - p) - ((x0 - p) . n)n
00665     cv::subtract(x0_p__, temp1__, temp1__);
00666 
00667     // d = ||(x0 - p) - ((x0 - p) . n)n||
00668     cv::multiply(n_x, n_x, n_x);
00669     cv::multiply(n_y, n_y, n_y);
00670     cv::multiply(n_z, n_z, n_z);
00671     cv::reduce(temp1__.reshape(1), temp3__, 1, CV_REDUCE_SUM);
00672     cv::sqrt(temp3__, temp3__);
00673 
00674 
00676     // Line 2
00678 
00679     // d = ||(x0 - p) - ((x0 - p) . n)n||
00680 
00681     n = cv::Scalar(model.i2, model.j2, model.k2);
00682     temp1__.setTo(n);
00683 
00684     // (x0 - p)
00685     cv::subtract(p, x0, x0_p__);
00686 
00687     // (x0 - p) . n
00688     cv::multiply(x0_p__, temp1__, temp2__);
00689     cv::reduce(temp2__.reshape(1), x0_p_dot_n__, 1, CV_REDUCE_SUM);
00690 
00691     // ((x0 - p) . n)n
00692     cv::multiply(n_x, x0_p_dot_n__, n_x);
00693     cv::multiply(n_y, x0_p_dot_n__, n_y);
00694     cv::multiply(n_z, x0_p_dot_n__, n_z);
00695 
00696     // (x0 - p) - ((x0 - p) . n)n
00697     cv::subtract(x0_p__, temp1__, temp1__);
00698 
00699     // d = ||(x0 - p) - ((x0 - p) . n)n||
00700     cv::multiply(n_x, n_x, n_x);
00701     cv::multiply(n_y, n_y, n_y);
00702     cv::multiply(n_z, n_z, n_z);
00703     cv::reduce(temp1__.reshape(1), norms, 1, CV_REDUCE_SUM);
00704     cv::sqrt(norms, norms);
00705 
00706     // Use the minimum distance to either line.
00707     norms = cv::min(norms, temp3__);
00708   }
00709 }


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