Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009 #include <grid_map_core/Polygon.hpp>
00010
00011 #include <Eigen/Core>
00012 #include <Eigen/Geometry>
00013
00014 #include <limits>
00015
00016 namespace grid_map {
00017
00018 Polygon::Polygon()
00019 : timestamp_(0)
00020 {
00021 }
00022
00023 Polygon::Polygon(std::vector<Position> vertices)
00024 : Polygon()
00025 {
00026 vertices_ = vertices;
00027 }
00028
00029 Polygon::~Polygon() {}
00030
00031 bool Polygon::isInside(const Position& point) const
00032 {
00033 int cross = 0;
00034 for (int i = 0, j = vertices_.size() - 1; i < vertices_.size(); j = i++) {
00035 if ( ((vertices_[i].y() > point.y()) != (vertices_[j].y() > point.y()))
00036 && (point.x() < (vertices_[j].x() - vertices_[i].x()) * (point.y() - vertices_[i].y()) /
00037 (vertices_[j].y() - vertices_[i].y()) + vertices_[i].x()) )
00038 {
00039 cross++;
00040 }
00041 }
00042 return bool(cross % 2);
00043 }
00044
00045 void Polygon::addVertex(const Position& vertex)
00046 {
00047 vertices_.push_back(vertex);
00048 }
00049
00050 const Position& Polygon::getVertex(const size_t index) const
00051 {
00052 return vertices_.at(index);
00053 }
00054
00055 void Polygon::removeVertices()
00056 {
00057 vertices_.clear();
00058 }
00059
00060 const Position& Polygon::operator [](const size_t index) const
00061 {
00062 return getVertex(index);
00063 }
00064
00065 const std::vector<Position>& Polygon::getVertices() const
00066 {
00067 return vertices_;
00068 }
00069
00070 const size_t Polygon::nVertices() const
00071 {
00072 return vertices_.size();
00073 }
00074
00075 const std::string& Polygon::getFrameId() const
00076 {
00077 return frameId_;
00078 }
00079
00080 void Polygon::setFrameId(const std::string& frameId)
00081 {
00082 frameId_ = frameId;
00083 }
00084
00085 uint64_t Polygon::getTimestamp() const
00086 {
00087 return timestamp_;
00088 }
00089
00090 void Polygon::setTimestamp(const uint64_t timestamp)
00091 {
00092 timestamp_ = timestamp;
00093 }
00094
00095 void Polygon::resetTimestamp()
00096 {
00097 timestamp_ = 0.0;
00098 }
00099
00100 const double Polygon::getArea() const
00101 {
00102 double area = 0.0;
00103 int j = vertices_.size() - 1;
00104 for (int i = 0; i < vertices_.size(); i++) {
00105 area += (vertices_.at(j).x() + vertices_.at(i).x())
00106 * (vertices_.at(j).y() - vertices_.at(i).y());
00107 j = i;
00108 }
00109 return std::abs(area / 2.0);
00110 }
00111
00112 Position Polygon::getCentroid() const
00113 {
00114 Position centroid = Position::Zero();
00115 std::vector<Position> vertices = getVertices();
00116 vertices.push_back(vertices.at(0));
00117 double area = 0.0;
00118 for (int i = 0; i < vertices.size() - 1; i++) {
00119 const double a = vertices[i].x() * vertices[i+1].y() - vertices[i+1].x() * vertices[i].y();
00120 area += a;
00121 centroid.x() += a * (vertices[i].x() + vertices[i+1].x());
00122 centroid.y() += a * (vertices[i].y() + vertices[i+1].y());
00123 }
00124 area *= 0.5;
00125 centroid /= (6.0 * area);
00126 return centroid;
00127 }
00128
00129 void Polygon::getBoundingBox(Position& center, Length& length) const
00130 {
00131 double minX = std::numeric_limits<double>::infinity();
00132 double maxX = -std::numeric_limits<double>::infinity();
00133 double minY = std::numeric_limits<double>::infinity();
00134 double maxY = -std::numeric_limits<double>::infinity();
00135 for (const auto& vertex : vertices_) {
00136 if (vertex.x() > maxX) maxX = vertex.x();
00137 if (vertex.y() > maxY) maxY = vertex.y();
00138 if (vertex.x() < minX) minX = vertex.x();
00139 if (vertex.y() < minY) minY = vertex.y();
00140 }
00141 center.x() = (minX + maxX) / 2.0;
00142 center.y() = (minY + maxY) / 2.0;
00143 length.x() = (maxX - minX);
00144 length.y() = (maxY - minY);
00145 }
00146
00147 bool Polygon::convertToInequalityConstraints(Eigen::MatrixXd& A, Eigen::VectorXd& b) const
00148 {
00149 Eigen::MatrixXd V(nVertices(), 2);
00150 for (unsigned int i = 0; i < nVertices(); ++i)
00151 V.row(i) = vertices_[i];
00152
00153
00154
00155
00156 Eigen::MatrixXi k;
00157 k.resizeLike(V);
00158 for (unsigned int i = 0; i < V.rows(); ++i)
00159 k.row(i) << i, (i+1) % V.rows();
00160 Eigen::RowVectorXd c = V.colwise().mean();
00161 V.rowwise() -= c;
00162 A = Eigen::MatrixXd::Constant(k.rows(), V.cols(), NAN);
00163
00164 unsigned int rc = 0;
00165 for (unsigned int ix = 0; ix < k.rows(); ++ix) {
00166 Eigen::MatrixXd F(2, V.cols());
00167 F.row(0) << V.row(k(ix, 0));
00168 F.row(1) << V.row(k(ix, 1));
00169 Eigen::FullPivLU<Eigen::MatrixXd> luDecomp(F);
00170 if (luDecomp.rank() == F.rows()) {
00171 A.row(rc) = F.colPivHouseholderQr().solve(Eigen::VectorXd::Ones(F.rows()));
00172 ++rc;
00173 }
00174 }
00175
00176 A = A.topRows(rc);
00177 b = Eigen::VectorXd::Ones(A.rows());
00178 b = b + A * c.transpose();
00179
00180 return true;
00181 }
00182
00183 bool Polygon::thickenLine(const double thickness)
00184 {
00185 if (vertices_.size() != 2) return false;
00186 const Vector connection(vertices_[1] - vertices_[0]);
00187 const Vector orthogonal = thickness * Vector(connection.y(), -connection.x()).normalized();
00188 std::vector<Position> newVertices;
00189 newVertices.reserve(4);
00190 newVertices.push_back(vertices_[0] + orthogonal);
00191 newVertices.push_back(vertices_[0] - orthogonal);
00192 newVertices.push_back(vertices_[1] - orthogonal);
00193 newVertices.push_back(vertices_[1] + orthogonal);
00194 vertices_ = newVertices;
00195 return true;
00196 }
00197
00198 bool Polygon::offsetInward(const double margin)
00199 {
00200
00201
00202 std::vector<Eigen::Array2i> neighbourIndices;
00203 const unsigned int n = nVertices();
00204 neighbourIndices.resize(n);
00205 for (unsigned int i = 0; i < n; ++i) {
00206 neighbourIndices[i] << (i > 0 ? (i-1)%n : n-1), (i + 1) % n;
00207 }
00208
00209 std::vector<Position> copy(vertices_);
00210 for (unsigned int i = 0; i < neighbourIndices.size(); ++i) {
00211 Eigen::Vector2d v1 = vertices_[neighbourIndices[i](0)] - vertices_[i];
00212 Eigen::Vector2d v2 = vertices_[neighbourIndices[i](1)] - vertices_[i];
00213 v1.normalize();
00214 v2.normalize();
00215 const double angle = acos(v1.dot(v2));
00216 copy[i] += margin / sin(angle) * (v1 + v2);
00217 }
00218 vertices_ = copy;
00219 return true;
00220 }
00221
00222 std::vector<Polygon> Polygon::triangulate(const TriangulationMethods& method) const
00223 {
00224
00225
00226 std::vector<Polygon> polygons;
00227 if (vertices_.size() < 3)
00228 return polygons;
00229
00230 size_t nPolygons = vertices_.size() - 2;
00231 polygons.reserve(nPolygons);
00232
00233 if (nPolygons < 1) {
00234
00235 polygons.push_back(*this);
00236 } else {
00237
00238 for (size_t i = 0; i < nPolygons; ++i) {
00239 Polygon polygon({vertices_[0], vertices_[i + 1], vertices_[i + 2]});
00240 polygons.push_back((polygon));
00241 }
00242 }
00243
00244 return polygons;
00245 }
00246
00247 Polygon Polygon::fromCircle(const Position center, const double radius,
00248 const int nVertices)
00249 {
00250 Eigen::Vector2d centerToVertex(radius, 0.0), centerToVertexTemp;
00251
00252 Polygon polygon;
00253 for (int j = 0; j < nVertices; j++) {
00254 double theta = j * 2 * M_PI / (nVertices - 1);
00255 Eigen::Rotation2D<double> rot2d(theta);
00256 centerToVertexTemp = rot2d.toRotationMatrix() * centerToVertex;
00257 polygon.addVertex(center + centerToVertexTemp);
00258 }
00259 return polygon;
00260 }
00261
00262 Polygon Polygon::convexHullOfTwoCircles(const Position center1,
00263 const Position center2, const double radius,
00264 const int nVertices)
00265 {
00266 if (center1 == center2) return fromCircle(center1, radius, nVertices);
00267 Eigen::Vector2d centerToVertex, centerToVertexTemp;
00268 centerToVertex = center2 - center1;
00269 centerToVertex.normalize();
00270 centerToVertex *= radius;
00271
00272 grid_map::Polygon polygon;
00273 for (int j = 0; j < ceil(nVertices / 2.0); j++) {
00274 double theta = M_PI_2 + j * M_PI / (ceil(nVertices / 2.0) - 1);
00275 Eigen::Rotation2D<double> rot2d(theta);
00276 centerToVertexTemp = rot2d.toRotationMatrix() * centerToVertex;
00277 polygon.addVertex(center1 + centerToVertexTemp);
00278 }
00279 for (int j = 0; j < ceil(nVertices / 2.0); j++) {
00280 double theta = 3 * M_PI_2 + j * M_PI / (ceil(nVertices / 2.0) - 1);
00281 Eigen::Rotation2D<double> rot2d(theta);
00282 centerToVertexTemp = rot2d.toRotationMatrix() * centerToVertex;
00283 polygon.addVertex(center2 + centerToVertexTemp);
00284 }
00285 return polygon;
00286 }
00287
00288 Polygon Polygon::convexHull(Polygon& polygon1, Polygon& polygon2)
00289 {
00290 std::vector<Position> vertices;
00291 vertices.reserve(polygon1.nVertices() + polygon2.nVertices());
00292 vertices.insert(vertices.end(), polygon1.getVertices().begin(), polygon1.getVertices().end());
00293 vertices.insert(vertices.end(), polygon2.getVertices().begin(), polygon2.getVertices().end());
00294
00295 std::vector<Position> hull(vertices.size()+1);
00296
00297
00298 std::sort(vertices.begin(), vertices.end(), sortVertices);
00299
00300 int k = 0;
00301
00302 for (int i = 0; i < vertices.size(); ++i) {
00303 while (k >= 2
00304 && computeCrossProduct2D(hull.at(k - 1) - hull.at(k - 2),
00305 vertices.at(i) - hull.at(k - 2)) <= 0)
00306 k--;
00307 hull.at(k++) = vertices.at(i);
00308 }
00309
00310
00311 for (int i = vertices.size() - 2, t = k + 1; i >= 0; i--) {
00312 while (k >= t
00313 && computeCrossProduct2D(hull.at(k - 1) - hull.at(k - 2),
00314 vertices.at(i) - hull.at(k - 2)) <= 0)
00315 k--;
00316 hull.at(k++) = vertices.at(i);
00317 }
00318 hull.resize(k - 1);
00319
00320 Polygon polygon(hull);
00321 return polygon;
00322 }
00323
00324 bool Polygon::sortVertices(const Eigen::Vector2d& vector1,
00325 const Eigen::Vector2d& vector2)
00326 {
00327 return (vector1.x() < vector2.x()
00328 || (vector1.x() == vector2.x() && vector1.y() < vector2.y()));
00329 }
00330
00331 double Polygon::computeCrossProduct2D(const Eigen::Vector2d& vector1,
00332 const Eigen::Vector2d& vector2)
00333 {
00334 return (vector1.x() * vector2.y() - vector1.y() * vector2.x());
00335 }
00336
00337 }
00338