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 #include <stdint.h>
00031
00032 #include <swri_geometry_util/intersection.h>
00033
00034 #define HAVE_INT64_T_64 # Prevents conflict with OpenCV typedef of int64
00035 #include <geos/geom/CoordinateArraySequence.h>
00036 #include <geos/geom/GeometryFactory.h>
00037 #include <geos/geom/Polygon.h>
00038 #include <geos/util/TopologyException.h>
00039 #undef HAVE_INT64_T_64
00040
00041 namespace swri_geometry_util
00042 {
00043 bool LineIntersection(
00044 const cv::Vec2d& p1,
00045 const cv::Vec2d& p2,
00046 const cv::Vec2d& p3,
00047 const cv::Vec2d& p4,
00048 cv::Vec2d& c)
00049 {
00050 double d = (p1[0] - p2[0]) * (p3[1] - p4[1]) - (p1[1] - p2[1]) * (p3[0] - p4[0]);
00051 if (d == 0)
00052 {
00053 return false;
00054 }
00055
00056 double n_a = (p1[0] * p2[1] - p1[1] * p2[0]) * (p3[0] - p4[0]) - (p1[0] - p2[0]) * (p3[0] * p4[1] - p3[1] * p4[0]);
00057 double n_b = (p1[0] * p2[1] - p1[1] * p2[0]) * (p3[1] - p4[1]) - (p1[1] - p2[1]) * (p3[0] * p4[1] - p3[1] * p4[0]);
00058
00059 c[0] = n_a / d;
00060 c[1] = n_b / d;
00061
00062 return true;
00063 }
00064
00065 bool LineSegmentIntersection(
00066 const cv::Vec2d& p1,
00067 const cv::Vec2d& p2,
00068 const cv::Vec2d& p3,
00069 const cv::Vec2d& p4,
00070 cv::Vec2d& c)
00071 {
00072
00073
00074
00075
00076 if (p1 == p2)
00077 {
00078 if (PointOnLineSegment(p1, p3, p4))
00079 {
00080 c = p1;
00081 return true;
00082 }
00083
00084 return false;
00085 }
00086 else if (p3 == p4)
00087 {
00088 if (PointOnLineSegment(p3, p1, p2))
00089 {
00090 c = p3;
00091 return true;
00092 }
00093
00094 return false;
00095 }
00096
00097 cv::Point2d p(p1);
00098 cv::Point2d r(p2 - p1);
00099 cv::Point2d q(p3);
00100 cv::Point2d s(p4 - p3);
00101 cv::Point2d qp(q - p);
00102
00103 double rs = r.cross(s);
00104 if (std::fabs(rs) > std::numeric_limits<float>::epsilon())
00105 {
00106
00107
00108 double t = qp.cross(cv::Point2d(s.x / rs, s.y / rs));
00109 double u = (qp * -1).cross(cv::Point2d(r.x / -rs, r.y / -rs));
00110
00111 if (u >= 0 && t >= 0 && u <= 1.0 && t <= 1.0)
00112 {
00113
00114 c = p + t * r;
00115 return true;
00116 }
00117 else
00118 {
00119
00120 return false;
00121 }
00122 }
00123 else if (std::fabs(qp.cross(r)) > std::numeric_limits<float>::epsilon())
00124 {
00125
00126 return false;
00127 }
00128 else
00129 {
00130
00131 double rlen = r.dot(r);
00132 cv::Point2d unit_r(r.x / rlen, r.y / rlen);
00133 double t0 = qp.dot(unit_r);
00134 double t1 = t0 + s.dot(unit_r);
00135
00136 if (t0 > t1)
00137 {
00138 std::swap(t0, t1);
00139 }
00140
00141 if (t0 <= 1.0 && t1 >= 0.0)
00142 {
00143
00144
00145 double t = std::max(0.0, t0);
00146 c = p + t * r;
00147 return true;
00148 }
00149
00150
00151 return false;
00152 }
00153 }
00154
00155 bool PointOnLineSegment(
00156 const cv::Vec2d& p1,
00157 const cv::Vec2d& p2,
00158 const cv::Vec2d& p3)
00159 {
00160
00161 if (((p2[0] - p1[0]) * (p3[1] - p1[0])) - ((p3[0] - p1[0]) * (p2[1] - p1[1])) > std::numeric_limits<float>::epsilon())
00162 {
00163 return false;
00164 }
00165
00166 if (p2[0] != p3[0])
00167 {
00168 return (p1[0] <= p3[0] && p2[0] <= p1[0]) || (p1[0] <= p2[0] && p3[0] <= p1[0]);
00169 }
00170 else
00171 {
00172 return (p1[1] <= p3[1] && p2[1] <= p1[1]) || (p1[1] <= p2[1] && p3[1] <= p1[1]);
00173 }
00174 }
00175
00176 bool PolygonsIntersect(
00177 const std::vector<cv::Vec2d>& a,
00178 const std::vector<cv::Vec2d>& b)
00179 {
00180
00181 geos::geom::CoordinateSequence* a_coords = new geos::geom::CoordinateArraySequence();
00182 for (size_t i = 0; i < a.size(); i++)
00183 {
00184 a_coords->add(geos::geom::Coordinate(a[i][0], a[i][1]));
00185 }
00186 a_coords->add(a_coords->front());
00187
00188 geos::geom::LinearRing* a_ring = geos::geom::GeometryFactory::getDefaultInstance()->createLinearRing(a_coords);
00189 geos::geom::Polygon* a_polygon = geos::geom::GeometryFactory::getDefaultInstance()->createPolygon(a_ring, 0);
00190 a_polygon->normalize();
00191
00192
00193 geos::geom::CoordinateSequence* b_coords = new geos::geom::CoordinateArraySequence();
00194 for (size_t i = 0; i < b.size(); i++)
00195 {
00196 b_coords->add(geos::geom::Coordinate(b[i][0], b[i][1]));
00197 }
00198 b_coords->add(b_coords->front());
00199
00200 geos::geom::LinearRing* b_ring = geos::geom::GeometryFactory::getDefaultInstance()->createLinearRing(b_coords);
00201 geos::geom::Polygon* b_polygon = geos::geom::GeometryFactory::getDefaultInstance()->createPolygon(b_ring, 0);
00202 b_polygon->normalize();
00203
00204 bool intersects = a_polygon->intersects(b_polygon);
00205
00206
00207 delete a_polygon;
00208 delete b_polygon;
00209
00210 return intersects;
00211 }
00212
00213 double PolygonIntersectionArea(
00214 const std::vector<cv::Vec2d>& a,
00215 const std::vector<cv::Vec2d>& b)
00216 {
00217 if (a.size() < 3 || b.size() < 3)
00218 {
00219 return 0;
00220 }
00221
00222 double area = 0;
00223
00224 geos::geom::CoordinateSequence* a_coords = new geos::geom::CoordinateArraySequence();
00225 for (size_t i = 0; i < a.size(); i++)
00226 {
00227 a_coords->add(geos::geom::Coordinate(a[i][0], a[i][1]));
00228 }
00229 a_coords->add(a_coords->front());
00230
00231 geos::geom::LinearRing* a_ring = geos::geom::GeometryFactory::getDefaultInstance()->createLinearRing(a_coords);
00232 geos::geom::Polygon* a_polygon = geos::geom::GeometryFactory::getDefaultInstance()->createPolygon(a_ring, 0);
00233 a_polygon->normalize();
00234
00235
00236 geos::geom::CoordinateSequence* b_coords = new geos::geom::CoordinateArraySequence();
00237 for (size_t i = 0; i < b.size(); i++)
00238 {
00239 b_coords->add(geos::geom::Coordinate(b[i][0], b[i][1]));
00240 }
00241 b_coords->add(b_coords->front());
00242
00243 geos::geom::LinearRing* b_ring = geos::geom::GeometryFactory::getDefaultInstance()->createLinearRing(b_coords);
00244 geos::geom::Polygon* b_polygon = geos::geom::GeometryFactory::getDefaultInstance()->createPolygon(b_ring, 0);
00245 b_polygon->normalize();
00246
00247 try
00248 {
00249 if (a_polygon->intersects(b_polygon))
00250 {
00251 area = a_polygon->intersection(b_polygon)->getArea();
00252 }
00253 }
00254 catch (const geos::util::TopologyException& e)
00255 {
00256
00257 }
00258
00259
00260 delete a_polygon;
00261 delete b_polygon;
00262
00263 return area;
00264 }
00265 }