123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264 |
- #pragma once
- #include <cmath>
- #include <AP_Common/AP_Common.h>
- template <typename T>
- struct Vector2
- {
- T x, y;
-
- constexpr Vector2<T>()
- : x(0)
- , y(0) {}
-
- constexpr Vector2<T>(const T x0, const T y0)
- : x(x0)
- , y(y0) {}
-
- void operator ()(const T x0, const T y0)
- {
- x= x0; y= y0;
- }
-
- bool operator ==(const Vector2<T> &v) const;
-
- bool operator !=(const Vector2<T> &v) const;
-
- Vector2<T> operator -(void) const;
-
- Vector2<T> operator +(const Vector2<T> &v) const;
-
- Vector2<T> operator -(const Vector2<T> &v) const;
-
- Vector2<T> operator *(const T num) const;
-
- Vector2<T> operator /(const T num) const;
-
- Vector2<T> &operator +=(const Vector2<T> &v);
-
- Vector2<T> &operator -=(const Vector2<T> &v);
-
- Vector2<T> &operator *=(const T num);
-
- Vector2<T> &operator /=(const T num);
-
- T operator *(const Vector2<T> &v) const;
-
- T operator %(const Vector2<T> &v) const;
-
-
- float angle(const Vector2<T> &v2) const;
-
-
- float angle(void) const;
-
- bool is_nan(void) const WARN_IF_UNUSED;
-
- bool is_inf(void) const WARN_IF_UNUSED;
-
- bool is_zero(void) const WARN_IF_UNUSED {
- return (fabsf(x) < FLT_EPSILON) && (fabsf(y) < FLT_EPSILON);
- }
-
- T & operator[](uint8_t i) {
- T *_v = &x;
- #if MATH_CHECK_INDEXES
- assert(i >= 0 && i < 2);
- #endif
- return _v[i];
- }
- const T & operator[](uint8_t i) const {
- const T *_v = &x;
- #if MATH_CHECK_INDEXES
- assert(i >= 0 && i < 2);
- #endif
- return _v[i];
- }
-
-
- void zero()
- {
- x = y = 0;
- }
-
- float length_squared() const;
-
- float length(void) const;
-
- void normalize();
-
- Vector2<T> normalized() const;
-
- void reflect(const Vector2<T> &n);
-
- void project(const Vector2<T> &v);
-
- Vector2<T> projected(const Vector2<T> &v);
-
-
- static Vector2<T> perpendicular(const Vector2<T> &pos_delta, const Vector2<T> &v1);
-
- static Vector2<T> closest_point(const Vector2<T> &p, const Vector2<T> &v, const Vector2<T> &w);
-
- static Vector2<T> closest_point(const Vector2<T> &p, const Vector2<T> &w);
-
-
-
- static float closest_distance_between_line_and_point_squared(const Vector2<T> &w1,
- const Vector2<T> &w2,
- const Vector2<T> &p);
-
-
-
- static float closest_distance_between_line_and_point(const Vector2<T> &w1,
- const Vector2<T> &w2,
- const Vector2<T> &p);
-
-
- static float closest_distance_between_lines_squared(const Vector2<T> &a1,
- const Vector2<T> &a2,
- const Vector2<T> &b1,
- const Vector2<T> &b2);
-
-
-
- static float closest_distance_between_radial_and_point_squared(const Vector2<T> &w,
- const Vector2<T> &p);
-
-
-
- static float closest_distance_between_radial_and_point(const Vector2<T> &w,
- const Vector2<T> &p);
-
-
-
- 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;
-
-
- 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;
-
- static bool point_on_segment(const Vector2<T>& point,
- const Vector2<T>& seg_start,
- const Vector2<T>& seg_end) WARN_IF_UNUSED {
- const float expected_run = seg_end.x-seg_start.x;
- const float intersection_run = point.x-seg_start.x;
-
- if (fabsf(expected_run) < FLT_EPSILON) {
- if (fabsf(intersection_run) > FLT_EPSILON) {
- return false;
- }
- } else {
- const float expected_slope = (seg_end.y-seg_start.y)/expected_run;
- const float intersection_slope = (point.y-seg_start.y)/intersection_run;
- if (fabsf(expected_slope - intersection_slope) > FLT_EPSILON) {
- return false;
- }
- }
-
- if (seg_start.x < seg_end.x) {
- if (point.x < seg_start.x || point.x > seg_end.x) {
- return false;
- }
- } else {
- if (point.x < seg_end.x || point.x > seg_start.x) {
- return false;
- }
- }
- if (seg_start.y < seg_end.y) {
- if (point.y < seg_start.y || point.y > seg_end.y) {
- return false;
- }
- } else {
- if (point.y < seg_end.y || point.y > seg_start.y) {
- return false;
- }
- }
- return true;
- }
- };
- typedef Vector2<int16_t> Vector2i;
- typedef Vector2<uint16_t> Vector2ui;
- typedef Vector2<int32_t> Vector2l;
- typedef Vector2<uint32_t> Vector2ul;
- typedef Vector2<float> Vector2f;
|