diff --git a/libraries/AP_Math/vector2.cpp b/libraries/AP_Math/vector2.cpp index e9bc0e86a8..de079fec64 100644 --- a/libraries/AP_Math/vector2.cpp +++ b/libraries/AP_Math/vector2.cpp @@ -285,6 +285,14 @@ Vector2 Vector2::projected(const Vector2 &v) return v * (*this * v)/(v*v); } +// extrapolate position given bearing (in degrees) and distance +template +void Vector2::offset_bearing(float bearing, float distance) +{ + x += cosf(radians(bearing)) * distance; + y += sinf(radians(bearing)) * distance; +} + // given a position pos_delta and a velocity v1 produce a vector // perpendicular to v1 maximising distance from p1 template @@ -435,6 +443,7 @@ template bool Vector2::is_nan(void) const; template bool Vector2::is_inf(void) const; template float Vector2::angle(const Vector2 &v) const; template float Vector2::angle(void) const; +template void Vector2::offset_bearing(float bearing, float distance); template bool Vector2::segment_intersection(const Vector2& seg1_start, const Vector2& seg1_end, const Vector2& seg2_start, const Vector2& seg2_end, Vector2& intersection); template bool Vector2::circle_segment_intersection(const Vector2& seg_start, const Vector2& seg_end, const Vector2& circle_center, float radius, Vector2& intersection); template Vector2 Vector2::perpendicular(const Vector2 &pos_delta, const Vector2 &v1); diff --git a/libraries/AP_Math/vector2.h b/libraries/AP_Math/vector2.h index 64dba5f411..0386ce260e 100644 --- a/libraries/AP_Math/vector2.h +++ b/libraries/AP_Math/vector2.h @@ -155,6 +155,9 @@ struct Vector2 // returns this vector projected onto v Vector2 projected(const Vector2 &v); + // adjust position by a given bearing (in degrees) and distance + void offset_bearing(float bearing, float distance); + // given a position p1 and a velocity v1 produce a vector // perpendicular to v1 maximising distance from p1 static Vector2 perpendicular(const Vector2 &pos_delta, const Vector2 &v1);