vector2.h 9.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. // Copyright 2010 Michael Smith, all rights reserved.
  14. // Derived closely from:
  15. /****************************************
  16. * 2D Vector Classes
  17. * By Bill Perone (billperone@yahoo.com)
  18. * Original: 9-16-2002
  19. * Revised: 19-11-2003
  20. * 18-12-2003
  21. * 06-06-2004
  22. *
  23. * Copyright 2003, This code is provided "as is" and you can use it freely as long as
  24. * credit is given to Bill Perone in the application it is used in
  25. ****************************************/
  26. #pragma once
  27. #include <cmath>
  28. #include <AP_Common/AP_Common.h>
  29. template <typename T>
  30. struct Vector2
  31. {
  32. T x, y;
  33. // trivial ctor
  34. constexpr Vector2<T>()
  35. : x(0)
  36. , y(0) {}
  37. // setting ctor
  38. constexpr Vector2<T>(const T x0, const T y0)
  39. : x(x0)
  40. , y(y0) {}
  41. // function call operator
  42. void operator ()(const T x0, const T y0)
  43. {
  44. x= x0; y= y0;
  45. }
  46. // test for equality
  47. bool operator ==(const Vector2<T> &v) const;
  48. // test for inequality
  49. bool operator !=(const Vector2<T> &v) const;
  50. // negation
  51. Vector2<T> operator -(void) const;
  52. // addition
  53. Vector2<T> operator +(const Vector2<T> &v) const;
  54. // subtraction
  55. Vector2<T> operator -(const Vector2<T> &v) const;
  56. // uniform scaling
  57. Vector2<T> operator *(const T num) const;
  58. // uniform scaling
  59. Vector2<T> operator /(const T num) const;
  60. // addition
  61. Vector2<T> &operator +=(const Vector2<T> &v);
  62. // subtraction
  63. Vector2<T> &operator -=(const Vector2<T> &v);
  64. // uniform scaling
  65. Vector2<T> &operator *=(const T num);
  66. // uniform scaling
  67. Vector2<T> &operator /=(const T num);
  68. // dot product
  69. T operator *(const Vector2<T> &v) const;
  70. // cross product
  71. T operator %(const Vector2<T> &v) const;
  72. // computes the angle between this vector and another vector
  73. // returns 0 if the vectors are parallel, and M_PI if they are antiparallel
  74. float angle(const Vector2<T> &v2) const;
  75. // computes the angle of this vector in radians, from 0 to 2pi,
  76. // from a unit vector(1,0); a (1,1) vector's angle is +M_PI/4
  77. float angle(void) const;
  78. // check if any elements are NAN
  79. bool is_nan(void) const WARN_IF_UNUSED;
  80. // check if any elements are infinity
  81. bool is_inf(void) const WARN_IF_UNUSED;
  82. // check if all elements are zero
  83. bool is_zero(void) const WARN_IF_UNUSED {
  84. return (fabsf(x) < FLT_EPSILON) && (fabsf(y) < FLT_EPSILON);
  85. }
  86. // allow a vector2 to be used as an array, 0 indexed
  87. T & operator[](uint8_t i) {
  88. T *_v = &x;
  89. #if MATH_CHECK_INDEXES
  90. assert(i >= 0 && i < 2);
  91. #endif
  92. return _v[i];
  93. }
  94. const T & operator[](uint8_t i) const {
  95. const T *_v = &x;
  96. #if MATH_CHECK_INDEXES
  97. assert(i >= 0 && i < 2);
  98. #endif
  99. return _v[i];
  100. }
  101. // zero the vector
  102. void zero()
  103. {
  104. x = y = 0;
  105. }
  106. // gets the length of this vector squared
  107. float length_squared() const;
  108. // gets the length of this vector
  109. float length(void) const;
  110. // normalizes this vector
  111. void normalize();
  112. // returns the normalized vector
  113. Vector2<T> normalized() const;
  114. // reflects this vector about n
  115. void reflect(const Vector2<T> &n);
  116. // projects this vector onto v
  117. void project(const Vector2<T> &v);
  118. // returns this vector projected onto v
  119. Vector2<T> projected(const Vector2<T> &v);
  120. // given a position p1 and a velocity v1 produce a vector
  121. // perpendicular to v1 maximising distance from p1
  122. static Vector2<T> perpendicular(const Vector2<T> &pos_delta, const Vector2<T> &v1);
  123. /*
  124. * Returns the point closest to p on the line segment (v,w).
  125. *
  126. * Comments and implementation taken from
  127. * http://stackoverflow.com/questions/849211/shortest-distance-between-a-point-and-a-line-segment
  128. */
  129. static Vector2<T> closest_point(const Vector2<T> &p, const Vector2<T> &v, const Vector2<T> &w);
  130. /*
  131. * Returns the point closest to p on the line segment (0,w).
  132. *
  133. * this is a simplification of closest point with a general segment, with v=(0,0)
  134. */
  135. static Vector2<T> closest_point(const Vector2<T> &p, const Vector2<T> &w);
  136. // w1 and w2 define a line segment
  137. // p is a point
  138. // returns the square of the closest distance between the line segment and the point
  139. static float closest_distance_between_line_and_point_squared(const Vector2<T> &w1,
  140. const Vector2<T> &w2,
  141. const Vector2<T> &p);
  142. // w1 and w2 define a line segment
  143. // p is a point
  144. // returns the closest distance between the line segment and the point
  145. static float closest_distance_between_line_and_point(const Vector2<T> &w1,
  146. const Vector2<T> &w2,
  147. const Vector2<T> &p);
  148. // a1->a2 and b2->v2 define two line segments
  149. // returns the square of the closest distance between the two line segments
  150. static float closest_distance_between_lines_squared(const Vector2<T> &a1,
  151. const Vector2<T> &a2,
  152. const Vector2<T> &b1,
  153. const Vector2<T> &b2);
  154. // w defines a line segment from the origin
  155. // p is a point
  156. // returns the square of the closest distance between the radial and the point
  157. static float closest_distance_between_radial_and_point_squared(const Vector2<T> &w,
  158. const Vector2<T> &p);
  159. // w defines a line segment from the origin
  160. // p is a point
  161. // returns the closest distance between the radial and the point
  162. static float closest_distance_between_radial_and_point(const Vector2<T> &w,
  163. const Vector2<T> &p);
  164. // find the intersection between two line segments
  165. // returns true if they intersect, false if they do not
  166. // the point of intersection is returned in the intersection argument
  167. static bool segment_intersection(const Vector2<T>& seg1_start, const Vector2<T>& seg1_end, const Vector2<T>& seg2_start, const Vector2<T>& seg2_end, Vector2<T>& intersection) WARN_IF_UNUSED;
  168. // find the intersection between a line segment and a circle
  169. // returns true if they intersect and intersection argument is updated with intersection closest to seg_start
  170. static bool circle_segment_intersection(const Vector2<T>& seg_start, const Vector2<T>& seg_end, const Vector2<T>& circle_center, float radius, Vector2<T>& intersection) WARN_IF_UNUSED;
  171. // check if a point falls on the line segment from seg_start to seg_end
  172. static bool point_on_segment(const Vector2<T>& point,
  173. const Vector2<T>& seg_start,
  174. const Vector2<T>& seg_end) WARN_IF_UNUSED {
  175. const float expected_run = seg_end.x-seg_start.x;
  176. const float intersection_run = point.x-seg_start.x;
  177. // check slopes are identical:
  178. if (fabsf(expected_run) < FLT_EPSILON) {
  179. if (fabsf(intersection_run) > FLT_EPSILON) {
  180. return false;
  181. }
  182. } else {
  183. const float expected_slope = (seg_end.y-seg_start.y)/expected_run;
  184. const float intersection_slope = (point.y-seg_start.y)/intersection_run;
  185. if (fabsf(expected_slope - intersection_slope) > FLT_EPSILON) {
  186. return false;
  187. }
  188. }
  189. // check for presence in bounding box
  190. if (seg_start.x < seg_end.x) {
  191. if (point.x < seg_start.x || point.x > seg_end.x) {
  192. return false;
  193. }
  194. } else {
  195. if (point.x < seg_end.x || point.x > seg_start.x) {
  196. return false;
  197. }
  198. }
  199. if (seg_start.y < seg_end.y) {
  200. if (point.y < seg_start.y || point.y > seg_end.y) {
  201. return false;
  202. }
  203. } else {
  204. if (point.y < seg_end.y || point.y > seg_start.y) {
  205. return false;
  206. }
  207. }
  208. return true;
  209. }
  210. };
  211. typedef Vector2<int16_t> Vector2i;
  212. typedef Vector2<uint16_t> Vector2ui;
  213. typedef Vector2<int32_t> Vector2l;
  214. typedef Vector2<uint32_t> Vector2ul;
  215. typedef Vector2<float> Vector2f;