Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- |
2 | /* |
||
3 | * polygon.cpp |
||
4 | * Copyright (C) Andrew Tridgell 2011 |
||
5 | * |
||
6 | * This file is free software: you can redistribute it and/or modify it |
||
7 | * under the terms of the GNU General Public License as published by the |
||
8 | * Free Software Foundation, either version 3 of the License, or |
||
9 | * (at your option) any later version. |
||
10 | * |
||
11 | * This file is distributed in the hope that it will be useful, but |
||
12 | * WITHOUT ANY WARRANTY; without even the implied warranty of |
||
13 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. |
||
14 | * See the GNU General Public License for more details. |
||
15 | * |
||
16 | * You should have received a copy of the GNU General Public License along |
||
17 | * with this program. If not, see <http://www.gnu.org/licenses/>. |
||
18 | */ |
||
19 | |||
20 | #include "AP_Math.h" |
||
21 | |||
22 | /* |
||
23 | The point in polygon algorithm is based on: |
||
24 | http://www.ecse.rpi.edu/Homepages/wrf/Research/Short_Notes/pnpoly.html |
||
25 | */ |
||
26 | |||
27 | |||
28 | /* |
||
29 | Polygon_outside(): test for a point in a polygon |
||
30 | Input: P = a point, |
||
31 | V[] = vertex points of a polygon V[n+1] with V[n]=V[0] |
||
32 | Return: true if P is outside the polygon |
||
33 | |||
34 | This does not take account of the curvature of the earth, but we |
||
35 | expect that to be very small over the distances involved in the |
||
36 | fence boundary |
||
37 | */ |
||
38 | bool Polygon_outside(const Vector2l &P, const Vector2l *V, unsigned n) |
||
39 | { |
||
40 | unsigned i, j; |
||
41 | bool outside = true; |
||
42 | for (i = 0, j = n-1; i < n; j = i++) { |
||
43 | if ((V[i].y > P.y) == (V[j].y > P.y)) { |
||
44 | continue; |
||
45 | } |
||
46 | int32_t dx1, dx2, dy1, dy2; |
||
47 | dx1 = P.x - V[i].x; |
||
48 | dx2 = V[j].x - V[i].x; |
||
49 | dy1 = P.y - V[i].y; |
||
50 | dy2 = V[j].y - V[i].y; |
||
51 | int8_t dx1s, dx2s, dy1s, dy2s, m1, m2; |
||
52 | #define sign(x) ((x)<0?-1:1) |
||
53 | dx1s = sign(dx1); |
||
54 | dx2s = sign(dx2); |
||
55 | dy1s = sign(dy1); |
||
56 | dy2s = sign(dy2); |
||
57 | m1 = dx1s * dy2s; |
||
58 | m2 = dx2s * dy1s; |
||
59 | // we avoid the 64 bit multiplies if we can based on sign checks. |
||
60 | if (dy2 < 0) { |
||
61 | if (m1 > m2) { |
||
62 | outside = !outside; |
||
63 | } else if (m1 < m2) { |
||
64 | continue; |
||
65 | } else if ( dx1 * (int64_t)dy2 > dx2 * (int64_t)dy1 ) { |
||
66 | outside = !outside; |
||
67 | } |
||
68 | } else { |
||
69 | if (m1 < m2) { |
||
70 | outside = !outside; |
||
71 | } else if (m1 > m2) { |
||
72 | continue; |
||
73 | } else if ( dx1 * (int64_t)dy2 < dx2 * (int64_t)dy1 ) { |
||
74 | outside = !outside; |
||
75 | } |
||
76 | } |
||
77 | } |
||
78 | return outside; |
||
79 | } |
||
80 | |||
81 | /* |
||
82 | check if a polygon is complete. |
||
83 | |||
84 | We consider a polygon to be complete if we have at least 4 points, |
||
85 | and the first point is the same as the last point. That is the |
||
86 | minimum requirement for the Polygon_outside function to work |
||
87 | */ |
||
88 | bool Polygon_complete(const Vector2l *V, unsigned n) |
||
89 | { |
||
90 | return (n >= 4 && V[n-1].x == V[0].x && V[n-1].y == V[0].y); |
||
91 | } |