Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include <teb_local_planner/obstacles.h>
00040 #include <ros/console.h>
00041 #include <ros/assert.h>
00042
00043
00044 namespace teb_local_planner
00045 {
00046
00047
00048 void PolygonObstacle::fixPolygonClosure()
00049 {
00050 if (vertices_.size()<2)
00051 return;
00052
00053 if (vertices_.front().isApprox(vertices_.back()))
00054 vertices_.pop_back();
00055 }
00056
00057 void PolygonObstacle::calcCentroid()
00058 {
00059 if (vertices_.empty())
00060 {
00061 centroid_.setConstant(NAN);
00062 ROS_WARN("PolygonObstacle::calcCentroid(): number of vertices is empty. the resulting centroid is a vector of NANs.");
00063 return;
00064 }
00065
00066
00067 if (noVertices()==1)
00068 {
00069 centroid_ = vertices_.front();
00070 return;
00071 }
00072
00073
00074 if (noVertices()==2)
00075 {
00076 centroid_ = 0.5*(vertices_.front() + vertices_.back());
00077 return;
00078 }
00079
00080
00081
00082 centroid_.setZero();
00083
00084
00085 double A = 0;
00086 for (int i=0; i < noVertices()-1; ++i)
00087 {
00088 A += vertices_.at(i).coeffRef(0) * vertices_.at(i+1).coeffRef(1) - vertices_.at(i+1).coeffRef(0) * vertices_.at(i).coeffRef(1);
00089 }
00090 A += vertices_.at(noVertices()-1).coeffRef(0) * vertices_.at(0).coeffRef(1) - vertices_.at(0).coeffRef(0) * vertices_.at(noVertices()-1).coeffRef(1);
00091 A *= 0.5;
00092
00093 if (A!=0)
00094 {
00095 for (int i=0; i < noVertices()-1; ++i)
00096 {
00097 double aux = (vertices_.at(i).coeffRef(0) * vertices_.at(i+1).coeffRef(1) - vertices_.at(i+1).coeffRef(0) * vertices_.at(i).coeffRef(1));
00098 centroid_ += ( vertices_.at(i) + vertices_.at(i+1) )*aux;
00099 }
00100 double aux = (vertices_.at(noVertices()-1).coeffRef(0) * vertices_.at(0).coeffRef(1) - vertices_.at(0).coeffRef(0) * vertices_.at(noVertices()-1).coeffRef(1));
00101 centroid_ += ( vertices_.at(noVertices()-1) + vertices_.at(0) )*aux;
00102 centroid_ /= (6*A);
00103 }
00104 else
00105 {
00106
00107 int i_cand = 0;
00108 int j_cand = 0;
00109 double max_dist = 0;
00110 for (int i=0; i< noVertices(); ++i)
00111 {
00112 for (int j=i+1; j< noVertices(); ++j)
00113 {
00114 double dist = (vertices_[j] - vertices_[i]).norm();
00115 if (dist > max_dist)
00116 {
00117 max_dist = dist;
00118 i_cand = i;
00119 j_cand = j;
00120 }
00121 }
00122 }
00123
00124 centroid_ = 0.5*(vertices_[i_cand] + vertices_[j_cand]);
00125 }
00126 }
00127
00128
00129
00130 Eigen::Vector2d PolygonObstacle::getClosestPoint(const Eigen::Vector2d& position) const
00131 {
00132
00133 if (noVertices() == 1)
00134 {
00135 return vertices_.front();
00136 }
00137
00138 if (noVertices() > 1)
00139 {
00140
00141 Eigen::Vector2d new_pt = closest_point_on_line_segment_2d(position, vertices_.at(0), vertices_.at(1));
00142
00143 if (noVertices() > 2)
00144 {
00145 double dist = (new_pt-position).norm();
00146 Eigen::Vector2d closest_pt = new_pt;
00147
00148
00149 for (int i=1; i<noVertices()-1; ++i)
00150 {
00151 new_pt = closest_point_on_line_segment_2d(position, vertices_.at(i), vertices_.at(i+1));
00152 double new_dist = (new_pt-position).norm();
00153 if (new_dist < dist)
00154 {
00155 dist = new_dist;
00156 closest_pt = new_pt;
00157 }
00158 }
00159
00160 new_pt = closest_point_on_line_segment_2d(position, vertices_.back(), vertices_.front());
00161 double new_dist = (new_pt-position).norm();
00162 if (new_dist < dist)
00163 return new_pt;
00164 else
00165 return closest_pt;
00166 }
00167 else
00168 {
00169 return new_pt;
00170 }
00171 }
00172
00173 ROS_ERROR("PolygonObstacle::getClosestPoint() cannot find any closest point. Polygon ill-defined?");
00174 return Eigen::Vector2d::Zero();
00175 }
00176
00177
00178 bool PolygonObstacle::checkLineIntersection(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double min_dist) const
00179 {
00180
00181
00182 for (int i=0; i<noVertices()-1; ++i)
00183 {
00184 if ( check_line_segments_intersection_2d(line_start, line_end, vertices_.at(i), vertices_.at(i+1)) )
00185 return true;
00186 }
00187 if (noVertices()==2)
00188 return false;
00189
00190 return check_line_segments_intersection_2d(line_start, line_end, vertices_.back(), vertices_.front());
00191 }
00192
00193
00194
00195
00196 void PolygonObstacle::toPolygonMsg(geometry_msgs::Polygon& polygon)
00197 {
00198 polygon.points.resize(vertices_.size());
00199 for (std::size_t i=0; i<vertices_.size(); ++i)
00200 {
00201 polygon.points[i].x = vertices_[i].x();
00202 polygon.points[i].y = vertices_[i].y();
00203 polygon.points[i].z = 0;
00204 }
00205 }
00206
00207
00208
00209
00210
00211
00212
00213
00214 }