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
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
00066 if (noVertices()==1)
00067 {
00068 centroid_ = vertices_.front();
00069 return;
00070 }
00071
00072
00073 if (noVertices()==2)
00074 {
00075 centroid_ = 0.5*(vertices_.front() + vertices_.back());
00076 return;
00077 }
00078
00079
00080
00081 centroid_.setZero();
00082
00083
00084 double A = 0;
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
00104 {
00105
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)
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
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
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)
00143 {
00144 double dist = (new_pt-position).norm();
00145 Eigen::Vector2d closest_pt = new_pt;
00146
00147
00148 for (int i=1; i<(int)noVertices()-1; ++i)
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
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;
00169 }
00170 }
00171
00172 ROS_ERROR("PolygonObstacle::getClosestPoint() cannot find any closest point. Polygon ill-defined?");
00173 return Eigen::Vector2d::Zero();
00174 }
00175
00176
00177 bool PolygonObstacle::checkLineIntersection(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double min_dist) const
00178 {
00179
00180
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)
00187 return false;
00188
00189 return check_line_segments_intersection_2d(line_start, line_end, vertices_.back(), vertices_.front());
00190 }
00191
00192
00193
00194
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 }