AP_Math: add comment to vector2f::point_on_segment

This commit is contained in:
Randy Mackay 2019-08-10 11:36:36 +09:00
parent 8912e2f98e
commit c7ca9c04f8
1 changed files with 1 additions and 0 deletions

View File

@ -216,6 +216,7 @@ struct Vector2
// returns true if they intersect and intersection argument is updated with intersection closest to seg_start
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;
// check if a point falls on the line segment from seg_start to seg_end
static bool point_on_segment(const Vector2<T>& point,
const Vector2<T>& seg_start,
const Vector2<T>& seg_end) WARN_IF_UNUSED {