comp_geometry.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Georgia Institute of Technology
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Georgia Institute of Technology nor the names of
00018  *     its contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 #include <cpl_visual_features/comp_geometry.h>
00035 #include <cmath>
00036 
00037 namespace cpl_visual_features
00038 {
00039 bool lineSegmentIntersection2D(pcl16::PointXYZ a1, pcl16::PointXYZ a2, pcl16::PointXYZ b1, pcl16::PointXYZ b2,
00040                                pcl16::PointXYZ& intersection)
00041 {
00042   if (!lineLineIntersection2D(a1, a2, b1, b2, intersection))
00043   {
00044     return false;
00045   }
00046   // Test if intersection is between a1 and a2
00047   return (pointIsBetweenOthers(intersection, a1, a2) && pointIsBetweenOthers(intersection, b1, b2));
00048 }
00049 
00050 bool lineLineIntersection2D(pcl16::PointXYZ a1, pcl16::PointXYZ a2, pcl16::PointXYZ b1, pcl16::PointXYZ b2,
00051                             pcl16::PointXYZ& intersection)
00052 {
00053   float denom = (a1.x-a2.x)*(b1.y-b2.y)-(a1.y-a2.y)*(b1.x-b2.x);
00054   if (denom == 0) // Parrallel lines
00055   {
00056     return false;
00057   }
00058   intersection.x = ((a1.x*a2.y - a1.y*a2.x)*(b1.x-b2.x) -
00059                     (a1.x - a2.x)*(b1.x*b2.y - b1.y*b2.x))/denom;
00060   intersection.y = ((a1.x*a2.y - a1.y*a2.x)*(b1.y-b2.y) -
00061                     (a1.y - a2.y)*(b1.x*b2.y - b1.y*b2.x))/denom;
00062   return true;
00063 }
00064 
00065 bool pointIsBetweenOthers(pcl16::PointXYZ& pt, pcl16::PointXYZ& x1, pcl16::PointXYZ& x2)
00066 {
00067   return (pt.x >= std::min(x1.x, x2.x) && pt.x <= std::max(x1.x, x2.x) &&
00068           pt.y >= std::min(x1.y, x2.y) && pt.y <= std::max(x1.y, x2.y));
00069 }
00070 
00071 double pointLineDistance2D(pcl16::PointXYZ& pt, pcl16::PointXYZ& a, pcl16::PointXYZ& b)
00072 {
00073   pcl16::PointXYZ q(a.x - pt.x, a.y - pt.y, 0.0);
00074   pcl16::PointXYZ n(b.x - a.x, b.y - a.y, 0.0);
00075   double norm_n = hypot(n.x, n.y);
00076   n.x /= norm_n;
00077   n.y /= norm_n;
00078   double q_dot_n = q.x*n.x+q.y*n.y;
00079   pcl16::PointXYZ l(q.x - q_dot_n*n.x, q.y - q_dot_n*n.y, 0.0);
00080   return hypot(l.x, l.y);
00081 }
00082 
00083 };


cpl_visual_features
Author(s): Tucker Hermans
autogenerated on Wed Nov 27 2013 11:52:35