APM:Libraries
vector2.h
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 // Copyright 2010 Michael Smith, all rights reserved.
17 
18 // Derived closely from:
19 /****************************************
20 * 2D Vector Classes
21 * By Bill Perone (billperone@yahoo.com)
22 * Original: 9-16-2002
23 * Revised: 19-11-2003
24 * 18-12-2003
25 * 06-06-2004
26 *
27 * © 2003, This code is provided "as is" and you can use it freely as long as
28 * credit is given to Bill Perone in the application it is used in
29 ****************************************/
30 #pragma once
31 
32 #include <cmath>
33 
34 template <typename T>
35 struct Vector2
36 {
37  T x, y;
38 
39  // trivial ctor
41  : x(0)
42  , y(0) {}
43 
44  // setting ctor
45  constexpr Vector2<T>(const T x0, const T y0)
46  : x(x0)
47  , y(y0) {}
48 
49  // function call operator
50  void operator ()(const T x0, const T y0)
51  {
52  x= x0; y= y0;
53  }
54 
55  // test for equality
56  bool operator ==(const Vector2<T> &v) const;
57 
58  // test for inequality
59  bool operator !=(const Vector2<T> &v) const;
60 
61  // negation
62  Vector2<T> operator -(void) const;
63 
64  // addition
65  Vector2<T> operator +(const Vector2<T> &v) const;
66 
67  // subtraction
68  Vector2<T> operator -(const Vector2<T> &v) const;
69 
70  // uniform scaling
71  Vector2<T> operator *(const T num) const;
72 
73  // uniform scaling
74  Vector2<T> operator /(const T num) const;
75 
76  // addition
78 
79  // subtraction
81 
82  // uniform scaling
83  Vector2<T> &operator *=(const T num);
84 
85  // uniform scaling
86  Vector2<T> &operator /=(const T num);
87 
88  // dot product
89  T operator *(const Vector2<T> &v) const;
90 
91  // cross product
92  T operator %(const Vector2<T> &v) const;
93 
94  // computes the angle between this vector and another vector
95  // returns 0 if the vectors are parallel, and M_PI if they are antiparallel
96  float angle(const Vector2<T> &v2) const;
97 
98  // check if any elements are NAN
99  bool is_nan(void) const;
100 
101  // check if any elements are infinity
102  bool is_inf(void) const;
103 
104  // check if all elements are zero
105  bool is_zero(void) const { return (fabsf(x) < FLT_EPSILON) && (fabsf(y) < FLT_EPSILON); }
106 
107  // allow a vector2 to be used as an array, 0 indexed
108  T & operator[](uint8_t i) {
109  T *_v = &x;
110 #if MATH_CHECK_INDEXES
111  assert(i >= 0 && i < 2);
112 #endif
113  return _v[i];
114  }
115 
116  const T & operator[](uint8_t i) const {
117  const T *_v = &x;
118 #if MATH_CHECK_INDEXES
119  assert(i >= 0 && i < 2);
120 #endif
121  return _v[i];
122  }
123 
124  // zero the vector
125  void zero()
126  {
127  x = y = 0;
128  }
129 
130  // gets the length of this vector squared
131  T length_squared() const
132  {
133  return (T)(*this * *this);
134  }
135 
136  // gets the length of this vector
137  float length(void) const;
138 
139  // normalizes this vector
140  void normalize()
141  {
142  *this/=length();
143  }
144 
145  // returns the normalized vector
147  {
148  return *this/length();
149  }
150 
151  // reflects this vector about n
152  void reflect(const Vector2<T> &n)
153  {
154  Vector2<T> orig(*this);
155  project(n);
156  *this= *this*2 - orig;
157  }
158 
159  // projects this vector onto v
160  void project(const Vector2<T> &v)
161  {
162  *this= v * (*this * v)/(v*v);
163  }
164 
165  // returns this vector projected onto v
167  {
168  return v * (*this * v)/(v*v);
169  }
170 
171  // given a position p1 and a velocity v1 produce a vector
172  // perpendicular to v1 maximising distance from p1
173  static Vector2<T> perpendicular(const Vector2<T> &pos_delta, const Vector2<T> &v1)
174  {
175  Vector2<T> perpendicular1 = Vector2<T>(-v1[1], v1[0]);
176  Vector2<T> perpendicular2 = Vector2<T>(v1[1], -v1[0]);
177  T d1 = perpendicular1 * pos_delta;
178  T d2 = perpendicular2 * pos_delta;
179  if (d1 > d2) {
180  return perpendicular1;
181  }
182  return perpendicular2;
183  }
184 
185  /*
186  * Returns the point closest to p on the line segment (v,w).
187  *
188  * Comments and implementation taken from
189  * http://stackoverflow.com/questions/849211/shortest-distance-between-a-point-and-a-line-segment
190  */
191  static Vector2<T> closest_point(const Vector2<T> &p, const Vector2<T> &v, const Vector2<T> &w)
192  {
193  // length squared of line segment
194  const float l2 = (v - w).length_squared();
195  if (l2 < FLT_EPSILON) {
196  // v == w case
197  return v;
198  }
199  // Consider the line extending the segment, parameterized as v + t (w - v).
200  // We find projection of point p onto the line.
201  // It falls where t = [(p-v) . (w-v)] / |w-v|^2
202  // We clamp t from [0,1] to handle points outside the segment vw.
203  const float t = ((p - v) * (w - v)) / l2;
204  if (t <= 0) {
205  return v;
206  } else if (t >= 1) {
207  return w;
208  } else {
209  return v + (w - v)*t;
210  }
211  }
212 
213  // w defines a line segment from the origin
214  // p is a point
215  // returns the closest distance between the radial and the point
217  const Vector2<T> &p)
218  {
219  const Vector2<T> closest = closest_point(p, Vector2<T>(0,0), w);
220  const Vector2<T> delta = closest - p;
221  return delta.length();
222  }
223 
224  // find the intersection between two line segments
225  // returns true if they intersect, false if they do not
226  // the point of intersection is returned in the intersection argument
227  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);
228 
229  // find the intersection between a line segment and a circle
230  // returns true if they intersect and intersection argument is updated with intersection closest to seg_start
231  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);
232 
233 };
234 
bool is_nan(void) const
Definition: vector2.cpp:66
Vector2< T > & operator*=(const T num)
Definition: vector2.cpp:45
Vector2< float > Vector2f
Definition: vector2.h:239
void project(const Vector2< T > &v)
Definition: vector2.h:160
Vector2< T > operator+(const Vector2< T > &v) const
Definition: vector2.cpp:103
Vector2< uint32_t > Vector2ul
Definition: vector2.h:238
Vector2< T > & operator-=(const Vector2< T > &v)
Definition: vector2.cpp:59
T & operator[](uint8_t i)
Definition: vector2.h:108
const T & operator[](uint8_t i) const
Definition: vector2.h:116
T operator%(const Vector2< T > &v) const
Definition: vector2.cpp:39
bool is_inf(void) const
Definition: vector2.cpp:72
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)
Definition: vector2.cpp:147
static float closest_distance_between_radial_and_point(const Vector2< T > &w, const Vector2< T > &p)
Definition: vector2.h:216
Vector2< int16_t > Vector2i
Definition: vector2.h:235
static Vector2< T > perpendicular(const Vector2< T > &pos_delta, const Vector2< T > &v1)
Definition: vector2.h:173
Vector2< T > & operator/=(const T num)
Definition: vector2.cpp:52
static Vector2< T > closest_point(const Vector2< T > &p, const Vector2< T > &v, const Vector2< T > &w)
Definition: vector2.h:191
Vector2< T > operator*(const T num) const
Definition: vector2.cpp:91
bool operator!=(const Vector2< T > &v) const
Definition: vector2.cpp:121
void reflect(const Vector2< T > &n)
Definition: vector2.h:152
Vector2< T > projected(const Vector2< T > &v)
Definition: vector2.h:166
static int8_t delta
Definition: RCOutput.cpp:21
float angle(const Vector2< T > &v2) const
Definition: vector2.cpp:127
T y
Definition: vector2.h:37
Vector2< T > normalized() const
Definition: vector2.h:146
T length_squared() const
Definition: vector2.h:131
bool operator==(const Vector2< T > &v) const
Definition: vector2.cpp:115
#define constexpr
Definition: AP_HAL_Macros.h:16
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)
Definition: vector2.cpp:180
void operator()(const T x0, const T y0)
Definition: vector2.h:50
float v
Definition: Printf.cpp:15
Vector2< T > operator-(void) const
Definition: vector2.cpp:109
float length(void) const
Definition: vector2.cpp:24
T x
Definition: vector2.h:37
Vector2< T > operator/(const T num) const
Definition: vector2.cpp:85
Vector2< int32_t > Vector2l
Definition: vector2.h:237
void normalize()
Definition: vector2.h:140
void zero()
Definition: vector2.h:125
bool is_zero(void) const
Definition: vector2.h:105
Vector2< T > & operator+=(const Vector2< T > &v)
Definition: vector2.cpp:78
void uint32_t num
Definition: systick.h:80
Vector2< uint16_t > Vector2ui
Definition: vector2.h:236