MinAreaRectangle.hpp
Go to the documentation of this file.
00001 // ========================================================================================
00002 //  ApproxMVBB
00003 //  Copyright (C) 2014 by Gabriel Nützi <nuetzig (at) imes (d0t) mavt (d0t) ethz (døt) ch>
00004 //
00005 //  This Source Code Form is subject to the terms of the Mozilla Public
00006 //  License, v. 2.0. If a copy of the MPL was not distributed with this
00007 //  file, You can obtain one at http://mozilla.org/MPL/2.0/.
00008 // ========================================================================================
00009 
00010 #ifndef ApproxMVBB_MinAreaRectangle_hpp
00011 #define ApproxMVBB_MinAreaRectangle_hpp
00012 
00013 #include <string>
00014 #include <vector>
00015 
00016 #include "ApproxMVBB/Config/Config.hpp"
00017 
00018 #include ApproxMVBB_TypeDefs_INCLUDE_FILE
00019 #include "ApproxMVBB/TypeDefsPoints.hpp"
00020 #include ApproxMVBB_AssertionDebug_INCLUDE_FILE
00021 
00022 #include "ApproxMVBB/AngleFunctions.hpp"
00023 #include "ApproxMVBB/PointFunctions.hpp"
00024 #include "ApproxMVBB/ConvexHull2D.hpp"
00025 
00026 namespace ApproxMVBB{
00030 class APPROXMVBB_EXPORT MinAreaRectangle {
00031 public:
00032     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00033     ApproxMVBB_DEFINE_MATRIX_TYPES
00034 
00035     ApproxMVBB_DEFINE_POINTS_CONFIG_TYPES
00036 
00041     template<typename Derived>
00042     MinAreaRectangle(const MatrixBase<Derived> & points)
00043         : m_p(points), m_convh(m_p) {
00044         EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived,2, Eigen::Dynamic)
00045         ApproxMVBB_ASSERTMSG( m_p.data() == points.derived().data() ," You store a temporary in a Ref<> which works here, but do you really want this?")
00046     }
00047 
00048     struct Box2d {
00049         EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00050         inline void reset() {
00051             m_p.setZero();
00052             m_u.setZero();
00053             m_v.setZero();
00054             m_area = 0.0;
00055             m_uL = 1.0;
00056             m_vL = 1.0;
00057         }
00058         Vector2 m_p;   
00059         Vector2 m_u;   
00060         Vector2 m_v;   
00061 
00062         PREC m_uL = 0.0;     
00063         PREC m_vL = 0.0;     
00064 
00065         PREC m_area = 0.0;
00066     };
00067 
00068     inline const Box2d &
00069     getMinRectangle() {
00070         return m_minBox;
00071     }
00072 
00073 
00074     void compute();
00075 
00076 private:
00077 
00078     using Vector2U = MyMatrix::Vector2<unsigned int>;
00079 
00080     void computeRectangle();
00081 
00082     struct Caliper {
00083         unsigned int m_idx = 0;   // index in m_hullIdx
00084         unsigned int m_ptIdx = 0; // index in m_p
00085         PREC m_currAngle = 0.0;
00086     };
00087 
00088     inline void adjustRectangle(){
00089 
00090         // The rectangle might be a slight parallelogram due to numerics
00091         //     |-l---*
00092         //  *  +++++++=================+
00093         //  |  +     |               | +
00094         //  h  +   | <-v  Rect     |   +
00095         //  |  + |               |     +
00096         //  -  +=================+++++++
00097         //     p        u
00098 
00099         PREC uNorm = m_minBox.m_u.norm();
00100         PREC vNorm = m_minBox.m_v.norm();
00101 
00102         // Normalize u direction (if u close to zero -> this becomes not finite)
00103         Vector2 uN = m_minBox.m_u.array() / uNorm;
00104         Vector2 vN = m_minBox.m_v.array() / vNorm;
00105 
00106         bool uF = uN.allFinite();
00107         bool vF = vN.allFinite();
00108 
00109         if(uF && vF){
00110 
00111             // make orthogonal (x axis is u)
00112             Vector2 uNT;
00113             uNT(0) = -uN(1);
00114             uNT(1) =  uN(0);
00115 
00116             PREC h =  uNT.dot(m_minBox.m_v);
00117             PREC l =  uN.dot (m_minBox.m_v);
00118 
00119             if(l>=0.0){
00120                 m_minBox.m_uL = uNorm + l;
00121             }else{
00122                 m_minBox.m_uL = uNorm - l;
00123                 m_minBox.m_p += uN*l; // move start point back
00124             }
00125 
00126             // if v vector pointed downwards (negative h)
00127             if( h<0 ){
00128                 // invert uNT (and switch u,v)
00129                 uNT *= -1.0;
00130                 m_minBox.m_u = uNT;
00131                 m_minBox.m_v = uN;
00132                 m_minBox.m_vL = m_minBox.m_uL;
00133                 m_minBox.m_uL = -h;
00134             }else{
00135                 m_minBox.m_vL = h;
00136                 m_minBox.m_u = uN;
00137                 m_minBox.m_v = uNT;
00138             }
00139 
00140         }else if(uF && !vF){
00141             // set u to normalized
00142             m_minBox.m_u    = uN;
00143             // adjust v direction
00144             m_minBox.m_v(0) = -uN(1);
00145             m_minBox.m_v(1) =  uN(0);
00146 
00147             m_minBox.m_uL = uNorm;
00148             m_minBox.m_vL = 0.0;
00149 
00150         }else if(!uF && vF){
00151             // set v to normalized
00152             m_minBox.m_v    = vN;
00153 
00154             // adjust u direction
00155             m_minBox.m_u(0) = -vN(1);
00156             m_minBox.m_u(1) =  vN(0);
00157 
00158             m_minBox.m_uL = 0.0;
00159             m_minBox.m_vL = vNorm;
00160         }else{
00161             // adjust both directions
00162             m_minBox.m_u(0) = 1.0; m_minBox.m_u(1) = 0.0;
00163             m_minBox.m_v(0) = 0.0;  m_minBox.m_v(1) = 1.0;
00164             m_minBox.m_uL = 0.0; m_minBox.m_vL = 0.0;
00165         }
00166 
00167     }
00168 
00169     inline void updateCalipers(PREC edgeAngle, Caliper (&c)[4]) {
00170 
00171         updateAngles(edgeAngle, c);
00172         for(unsigned char i=0; i<4; i++) {
00173             findVertex(c[i]);
00174         }
00175 
00176     }
00177 
00178     //determine caliper angles according to the box given with c[0].m_currAngle = edgeAngle;
00179     inline void updateAngles(PREC edgeAngle, Caliper (&c)[4]) {
00180         c[0].m_currAngle = AngleFunctions::mapTo2Pi(edgeAngle);
00181         c[1].m_currAngle = AngleFunctions::mapTo2Pi(c[0].m_currAngle + 0.5*M_PI);
00182         c[2].m_currAngle = AngleFunctions::mapTo2Pi(c[1].m_currAngle + 0.5*M_PI);
00183         c[3].m_currAngle = AngleFunctions::mapTo2Pi(c[2].m_currAngle + 0.5*M_PI);
00184 
00185         //        std::cout << "caliper 1 angle:" <<  c[0].m_currAngle << std::endl;
00186         //        std::cout << "caliper 2 angle:" <<  c[1].m_currAngle << std::endl;
00187         //        std::cout << "caliper 3 angle:" <<  c[2].m_currAngle << std::endl;
00188         //        std::cout << "caliper 4 angle:" <<  c[3].m_currAngle << std::endl;
00189     }
00190 
00191     // determine the vertex v for which the edge angle is greater than c.m_currAngle
00192     // the find algroithm starts at c.m_idx
00193     void findVertex(Caliper & c);
00194 
00195     void getBox(Caliper (&c)[4], Box2d & box);
00196 
00197 
00198     std::vector<unsigned int> m_hullIdx;
00199 
00200     std::vector<PREC> m_angles;
00201     Box2d m_minBox;
00202     const MatrixRef<const Matrix2Dyn> m_p;
00203 
00204     ConvexHull2D m_convh;
00205 
00206 };
00207 
00208 }
00209 #endif


asr_approx_mvbb
Author(s): Gassner Nikolai
autogenerated on Sat Jun 8 2019 20:21:49