line.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include "jsk_recognition_utils/geo/line.h"
00038 #include <jsk_topic_tools/log_utils.h>
00039 #include <cfloat>
00040 
00041 namespace jsk_recognition_utils
00042 {
00043   Line::Line(const Eigen::Vector3f& direction, const Eigen::Vector3f& origin)
00044     : direction_ (direction.normalized()), origin_(origin)
00045   {
00046 
00047   }
00048 
00049   void Line::getDirection(Eigen::Vector3f& output) const
00050   {
00051     output = direction_;
00052   }
00053 
00054   Eigen::Vector3f Line::getDirection() const
00055   {
00056     return direction_;
00057   }
00058   
00059   void Line::getOrigin(Eigen::Vector3f& output) const
00060   {
00061     output = origin_;
00062   }
00063 
00064   Eigen::Vector3f Line::getOrigin() const
00065   {
00066     return origin_;
00067   }
00068   
00069   void Line::foot(const Eigen::Vector3f& point, Eigen::Vector3f& output) const
00070   {
00071     const double alpha = computeAlpha(point);
00072     output = alpha * direction_ + origin_;
00073   }
00074 
00075   double Line::distanceToPoint(
00076     const Eigen::Vector3f& from, Eigen::Vector3f& foot_point) const
00077   {
00078     foot(from, foot_point);
00079     return (from - foot_point).norm();
00080   }
00081   
00082   double Line::distanceToPoint(const Eigen::Vector3f& from) const
00083   {
00084     Eigen::Vector3f foot_point;
00085     return distanceToPoint(from, foot_point);
00086   }
00087 
00088   double Line::angle(const Line& other) const
00089   {
00090     double dot = fabs(direction_.dot(other.direction_));
00091     if (dot > 1.0) {
00092       return M_PI / 2.0;
00093     }
00094     else {
00095       double theta = acos(dot);
00096       if (theta > M_PI / 2.0) {
00097         return M_PI / 2.0 - theta;
00098       }
00099       else {
00100         return theta;
00101       }
00102     }
00103   }
00104 
00105   bool Line::isParallel(const Line& other, double angle_threshold) const
00106   {
00107     return angle(other) < angle_threshold;
00108   }
00109 
00110   bool Line::isPerpendicular(const Line& other, double angle_threshold) const
00111   {
00112     return (M_PI / 2.0 - angle(other)) < angle_threshold;
00113   }
00114 
00115   bool Line::isSameDirection(const Line& other) const
00116   {
00117     return direction_.dot(other.direction_) > 0;
00118   }
00119 
00120   Line::Ptr Line::flip()
00121   {
00122     Line::Ptr ret (new Line(-direction_, origin_));
00123     return ret;
00124   }
00125   
00126   Line::Ptr Line::midLine(const Line& other) const
00127   {
00128     Eigen::Vector3f new_directin = (direction_ + other.direction_).normalized();
00129     Eigen::Vector3f new_origin;
00130     other.foot(origin_, new_origin);
00131     Line::Ptr ret (new Line(new_directin, (new_origin + origin_) / 2.0));
00132     return ret;
00133   }
00134 
00135   void Line::parallelLineNormal(const Line& other, Eigen::Vector3f& output)
00136     const
00137   {
00138     Eigen::Vector3f foot_point;
00139     other.foot(origin_, foot_point);
00140     output = origin_ - foot_point;
00141   }
00142   
00143   Line::Ptr Line::fromCoefficients(const std::vector<float>& coefficients)
00144   {
00145     Eigen::Vector3f p(coefficients[0],
00146                       coefficients[1],
00147                       coefficients[2]);
00148     Eigen::Vector3f d(coefficients[3],
00149                       coefficients[4],
00150                       coefficients[5]);
00151     Line::Ptr ret(new Line(d, p));
00152     return ret;
00153   }
00154 
00155   double Line::distance(const Line& other) const
00156   {
00157     Eigen::Vector3f v12 = (other.origin_ - origin_);
00158     Eigen::Vector3f n = direction_.cross(other.direction_);
00159     return fabs(n.dot(v12)) / n.norm();
00160   }
00161 
00162   Line::Ptr Line::parallelLineOnAPoint(const Eigen::Vector3f& p) const
00163   {
00164     Line::Ptr ret (new Line(direction_, p));
00165     return ret;
00166   }
00167   
00168   double Line::computeAlpha(const Point& p) const
00169   {
00170     return p.dot(direction_) - origin_.dot(direction_);
00171   }
00172   
00173   PointPair Line::findEndPoints(const Vertices& points) const
00174   {
00175     double min_alpha = DBL_MAX;
00176     double max_alpha = - DBL_MAX;
00177     Point min_alpha_point, max_alpha_point;
00178     for (size_t i = 0; i < points.size(); i++) {
00179       Point p = points[i];
00180       double alpha = computeAlpha(p);
00181       if (alpha > max_alpha) {
00182         max_alpha_point = p;
00183         max_alpha = alpha;
00184       }
00185       if (alpha < min_alpha) {
00186         min_alpha_point = p;
00187         min_alpha = alpha;
00188       }
00189     }
00190     // JSK_ROS_INFO("min: %f", min_alpha);
00191     // JSK_ROS_INFO("max: %f", max_alpha);
00192     return boost::make_tuple<Point, Point>(min_alpha_point, max_alpha_point);
00193   }
00194 
00195   void Line::print()
00196   {
00197     JSK_ROS_INFO("d: [%f, %f, %f], p: [%f, %f, %f]", direction_[0], direction_[1], direction_[2],
00198              origin_[0], origin_[1], origin_[2]);
00199   }
00200 
00201   void Line::point(double alpha, Eigen::Vector3f& output)
00202   {
00203     output = alpha * direction_ + origin_;
00204   }
00205 
00206 }


jsk_recognition_utils
Author(s):
autogenerated on Wed Sep 16 2015 04:36:01