ContourHelper.cpp
Go to the documentation of this file.
00001 // ****************************************************************************
00002 // This file is part of the Integrating Vision Toolkit (IVT).
00003 //
00004 // The IVT is maintained by the Karlsruhe Institute of Technology (KIT)
00005 // (www.kit.edu) in cooperation with the company Keyetech (www.keyetech.de).
00006 //
00007 // Copyright (C) 2014 Karlsruhe Institute of Technology (KIT).
00008 // All rights reserved.
00009 //
00010 // Redistribution and use in source and binary forms, with or without
00011 // modification, are permitted provided that the following conditions are met:
00012 //
00013 // 1. Redistributions of source code must retain the above copyright
00014 //    notice, this list of conditions and the following disclaimer.
00015 //
00016 // 2. Redistributions in binary form must reproduce the above copyright
00017 //    notice, this list of conditions and the following disclaimer in the
00018 //    documentation and/or other materials provided with the distribution.
00019 //
00020 // 3. Neither the name of the KIT nor the names of its contributors may be
00021 //    used to endorse or promote products derived from this software
00022 //    without specific prior written permission.
00023 //
00024 // THIS SOFTWARE IS PROVIDED BY THE KIT AND CONTRIBUTORS “AS IS” AND ANY
00025 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00026 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00027 // DISCLAIMED. IN NO EVENT SHALL THE KIT OR CONTRIBUTORS BE LIABLE FOR ANY
00028 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00029 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00031 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00032 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
00033 // THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00034 // ****************************************************************************
00035 // ****************************************************************************
00036 // Filename:  ContourHelper.cpp
00037 // Authors:   Derick Beng Yuh, Pedram Azad
00038 // Date:      03.08.2010
00039 // ****************************************************************************
00040 
00041 #include "ContourHelper.h"
00042 #include "Math/Math2d.h"
00043 
00044 
00045 
00046 // ****************************************************************************
00047 // Helper function used for testing if a middle point (p2) lies above, below or
00048 // on the line between p1 and p3.
00049 // Above : function returns negative value
00050 // Below : function returns positive value
00051 // On    : function reurns 0
00052 // ****************************************************************************
00053 static inline float det(const Vec2d &p1, const Vec2d &p2, const Vec2d &p3)
00054 {
00055         return ((p1.x - p2.x) * (p3.y - p2.y)) - ((p3.x - p2.x) * (p1.y - p2.y));
00056 }
00057 
00058 static void BuildLowerHalfHull(const CVec2dArray &input, CVec2dArray &output)
00059 {
00060         // Repeatedly add the leftmost point to the hull, then test to see if a
00061         // convexity violation has occurred. If it has, fix things up  by removing
00062         // the next-to-last point in the output sequence until convexity is restored.
00063         const int nPoints = input.GetSize();
00064 
00065         for (int i = 0; i < nPoints; i++)
00066         {
00067                 output.AddElement(input[i]);
00068                 
00069                 while (output.GetSize() >= 3)
00070                 {
00071                         const int nLastIndex = output.GetSize() - 1;
00072                         
00073                         if (det(output[nLastIndex - 2], output[nLastIndex - 1], output[nLastIndex]) <= 0.0f) 
00074                                 output.DeleteElement(nLastIndex - 1);
00075                         else
00076                                 break;
00077                 }
00078         }
00079 }
00080 
00081 static void BuildUpperHalfHull(const CVec2dArray &input, CVec2dArray &output)
00082 {
00083         // Repeatedly add the rightmost point to the hull, then test to see if a
00084         // convexity violation has occurred. If it has, fix things up  by removing
00085         // the next-to-last point in the output sequence until convexity is restored.
00086         const int nPoints = input.GetSize();
00087 
00088         for (int i = nPoints - 1; i >= 0; i--)
00089         {
00090                 output.AddElement(input[i]);
00091                 
00092                 while (output.GetSize() >= 3)
00093                 {
00094                         const int nLastIndex = output.GetSize() - 1;
00095 
00096                         if (det(output[nLastIndex - 2], output[nLastIndex - 1], output[nLastIndex]) <= 0.0f) 
00097                                 output.DeleteElement(nLastIndex - 1);
00098                         else
00099                                 break;
00100                 }
00101         }
00102 }
00103 
00104 static void QuicksortX(CVec2dArray &pPoints, int nLow, int nHigh)
00105 {
00106         int i = nLow;
00107         int j = nHigh;
00108                 
00109         const float fX = pPoints[(nLow + nHigh) / 2].x;
00110 
00111         while (i <= j)
00112         {    
00113                 while (pPoints[i].x < fX) i++; 
00114                 while (pPoints[j].x > fX) j--;
00115             
00116                 if (i <= j)
00117                 {
00118                         Vec2d temp;
00119                         Math2d::SetVec(temp, pPoints[i]);
00120                         Math2d::SetVec(pPoints[i], pPoints[j]);
00121                         Math2d::SetVec(pPoints[j], temp);
00122                 
00123                         i++;
00124                         j--;
00125                 }
00126         }
00127 
00128         if (nLow < j) QuicksortX(pPoints, nLow, j);
00129         if (i < nHigh) QuicksortX(pPoints, i, nHigh);
00130 }
00131 
00132 
00133 void ContourHelper::ComputeConvexHull(const Vec2d *pPoints, int nPoints, Vec2d *pResultPoints, int &nResultPoints)
00134 {
00135         int i;
00136 
00137         CVec2dArray vertices(2 * nPoints);
00138     for (i = 0; i < nPoints; i++)       
00139                 vertices.AddElement(pPoints[i]);
00140 
00141         QuicksortX(vertices, 0, nPoints - 1);
00142         
00143         const int nLastPoint = vertices.GetSize() - 1;
00144     const Vec2d &left = vertices[0];
00145         const Vec2d &right = vertices[nLastPoint];
00146 
00147         // partition points on plane according to their position with
00148         // with respect to the line between left and right
00149         CVec2dArray upper(2 * nPoints), lower(2 * nPoints);
00150         upper.AddElement(left); // must be added before loop
00151         for (i = 1; i < nLastPoint; i++)
00152         {
00153                 const Vec2d &point = vertices[i];
00154 
00155                 if (det(left, point, right) < 0.0f)
00156                 {
00157                         // point is above the line between left and right 
00158                         upper.AddElement(point);
00159                 }
00160                 else
00161                 {
00162                         // point is below the line between left and right       
00163                         lower.AddElement(point);
00164                 }
00165         }
00166         lower.AddElement(right); // must be added after loop
00167 
00168         CVec2dArray hull;
00169         hull.AddElement(left);
00170         
00171         // first build lower hull
00172         BuildLowerHalfHull(lower, hull);
00173 
00174         // then build upper hull
00175         BuildUpperHalfHull(upper, hull);
00176 
00177         // add points to result
00178         nResultPoints = 0;
00179         const int nHullSize = hull.GetSize() - 1;
00180         for (i = 0; i < nHullSize; i++)
00181                 Math2d::SetVec(pResultPoints[nResultPoints++], hull[i]);
00182 }


asr_ivt
Author(s): Allgeyer Tobias, Hutmacher Robin, Kleinert Daniel, Meißner Pascal, Scholz Jonas, Stöckle Patrick
autogenerated on Thu Jun 6 2019 21:46:57