obstacles.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2016,
00006  *  TU Dortmund - Institute of Control Theory and Systems Engineering.
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the institute nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * Author: Christoph Rösmann
00037  *********************************************************************/
00038 
00039 #include <teb_local_planner/obstacles.h>
00040 #include <ros/console.h>
00041 // #include <teb_local_planner/misc.h>
00042 
00043 namespace teb_local_planner
00044 {
00045 
00046 
00047 void PolygonObstacle::fixPolygonClosure()
00048 {
00049   if (vertices_.size()<2)
00050     return;
00051   
00052   if (vertices_.front().isApprox(vertices_.back()))
00053     vertices_.pop_back();
00054 }
00055 
00056 void PolygonObstacle::calcCentroid()
00057 {
00058   if (vertices_.empty())
00059   {
00060     centroid_.setConstant(NAN);
00061     ROS_WARN("PolygonObstacle::calcCentroid(): number of vertices is empty. the resulting centroid is a vector of NANs.");
00062     return;
00063   }
00064   
00065   // if polygon is a point
00066   if (noVertices()==1)
00067   {
00068     centroid_ = vertices_.front();
00069     return;
00070   }
00071   
00072   // if polygon is a line:
00073   if (noVertices()==2)
00074   {
00075     centroid_ = 0.5*(vertices_.front() + vertices_.back());
00076     return;
00077   }
00078   
00079   // otherwise:
00080   
00081   centroid_.setZero();
00082     
00083   // calculate centroid (see wikipedia http://de.wikipedia.org/wiki/Geometrischer_Schwerpunkt#Polygon)
00084   double A = 0;  // A = 0.5 * sum_0_n-1 (x_i * y_{i+1} - x_{i+1} * y_i)
00085   for (int i=0; i<(int)noVertices()-1; ++i)
00086   {
00087     A += vertices_.at(i).coeffRef(0) * vertices_.at(i+1).coeffRef(1) - vertices_.at(i+1).coeffRef(0) * vertices_.at(i).coeffRef(1);
00088   }
00089   A += vertices_.at(noVertices()-1).coeffRef(0) * vertices_.at(0).coeffRef(1) - vertices_.at(0).coeffRef(0) * vertices_.at(noVertices()-1).coeffRef(1);
00090   A *= 0.5;
00091   
00092   if (A!=0)
00093   {
00094     for (int i=0; i<(int)noVertices()-1; ++i)
00095     {
00096       double aux = (vertices_.at(i).coeffRef(0) * vertices_.at(i+1).coeffRef(1) - vertices_.at(i+1).coeffRef(0) * vertices_.at(i).coeffRef(1));
00097       centroid_ +=  ( vertices_.at(i) + vertices_.at(i+1) )*aux;
00098     }
00099     double aux = (vertices_.at(noVertices()-1).coeffRef(0) * vertices_.at(0).coeffRef(1) - vertices_.at(0).coeffRef(0) * vertices_.at(noVertices()-1).coeffRef(1));
00100     centroid_ +=  ( vertices_.at(noVertices()-1) + vertices_.at(0) )*aux;
00101     centroid_ /= (6*A); 
00102   }
00103   else // A == 0 -> all points are placed on a 'perfect' line
00104   {
00105     // seach for the two outer points of the line with the maximum distance inbetween
00106     int i_cand = 0;
00107     int j_cand = 0;
00108     double min_dist = HUGE_VAL;
00109     for (int i=0; i<(int)noVertices(); ++i)
00110     {
00111       for (int j=i+1; j<(int)noVertices(); ++j) // start with j=i+1
00112       {
00113         double dist = (vertices_[j] - vertices_[i]).norm();
00114         if (dist < min_dist)
00115         {
00116           min_dist = dist;
00117           i_cand = i;
00118           j_cand = j;
00119         }
00120       }
00121     }
00122     // calc centroid of that line
00123     centroid_ = 0.5*(vertices_[i_cand] + vertices_[j_cand]);
00124   }
00125 }
00126 
00127 
00128 
00129 Eigen::Vector2d PolygonObstacle::getClosestPoint(const Eigen::Vector2d& position) const
00130 {
00131  // the polygon is a point
00132   if (noVertices() == 1)
00133   {
00134     return vertices_.front();
00135   }
00136   
00137   if (noVertices() > 1)
00138   {
00139     
00140     Eigen::Vector2d new_pt = closest_point_on_line_segment_2d(position, vertices_.at(0), vertices_.at(1));
00141     
00142     if (noVertices() > 2) // real polygon and not a line
00143     {
00144       double dist = (new_pt-position).norm();
00145       Eigen::Vector2d closest_pt = new_pt;
00146       
00147       // check each polygon edge
00148       for (int i=1; i<(int)noVertices()-1; ++i) // skip the first one, since we already checked it (new_pt)
00149       {
00150         new_pt = closest_point_on_line_segment_2d(position, vertices_.at(i), vertices_.at(i+1));
00151         double new_dist = (new_pt-position).norm();
00152         if (new_dist < dist)
00153         {
00154           dist = new_dist;
00155           closest_pt = new_pt;
00156         }
00157       }
00158       // afterwards we check the edge between goal and start (close polygon)
00159       new_pt = closest_point_on_line_segment_2d(position, vertices_.back(), vertices_.front());
00160       double new_dist = (new_pt-position).norm();
00161       if (new_dist < dist)
00162         return new_pt;
00163       else
00164         return closest_pt;
00165     }
00166     else
00167     {
00168       return new_pt; // closest point on line segment
00169     }
00170   }
00171   
00172   ROS_ERROR("PolygonObstacle::getClosestPoint() cannot find any closest point. Polygon ill-defined?");
00173   return Eigen::Vector2d::Zero(); // todo: maybe boost::optional?
00174 }
00175 
00176 
00177 bool PolygonObstacle::checkLineIntersection(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double min_dist) const
00178 {
00179   // Simple strategy, check all edge-line intersections until an intersection is found...
00180   // check each polygon edge
00181   for (unsigned int i=0; i<vertices_.size()-1; ++i)
00182   {
00183     if ( check_line_segments_intersection_2d(line_start, line_end, vertices_.at(i), vertices_.at(i+1)) ) 
00184       return true;
00185   }
00186   if (noVertices()==2) // if polygon is a line
00187     return false;
00188   
00189   return check_line_segments_intersection_2d(line_start, line_end, vertices_.back(), vertices_.front()); //otherwise close polygon
00190 }
00191 
00192 
00193 
00194 // implements toPolygonMsg() of the base class
00195 void PolygonObstacle::toPolygonMsg(geometry_msgs::Polygon& polygon)
00196 {
00197   polygon.points.resize(vertices_.size());
00198   for (std::size_t i=0; i<vertices_.size(); ++i)
00199   {
00200     polygon.points[i].x = vertices_[i].x();
00201     polygon.points[i].y = vertices_[i].y();
00202     polygon.points[i].z = 0;
00203   }
00204 }
00205 
00206 
00207 
00208 
00209 
00210 
00211 
00212 
00213 } // namespace teb_local_planner


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Oct 24 2016 05:31:15