mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Math: add Vector2f::circle_segment_intersection
This commit is contained in:
parent
a655c36159
commit
c28cfcdc27
@ -173,6 +173,70 @@ bool Vector2<T>::segment_intersection(const Vector2<T>& seg1_start, const Vector
|
||||
}
|
||||
}
|
||||
|
||||
// find the intersection between a line segment and a circle
|
||||
// returns true if they intersect and intersection argument is updated with intersection closest to seg_start
|
||||
// solution adapted from http://stackoverflow.com/questions/1073336/circle-line-segment-collision-detection-algorithm
|
||||
template <typename T>
|
||||
bool Vector2<T>::circle_segment_intersection(const Vector2<T>& seg_start, const Vector2<T>& seg_end, const Vector2<T>& circle_center, float radius, Vector2<T>& intersection)
|
||||
{
|
||||
// calculate segment start and end as offsets from circle's center
|
||||
const Vector2f seg_start_local = seg_start - circle_center;
|
||||
|
||||
// calculate vector from start to end
|
||||
const Vector2f seg_end_minus_start = seg_end - seg_start;
|
||||
|
||||
const float a = sq(seg_end_minus_start.x) + sq(seg_end_minus_start.y);
|
||||
const float b = 2 * ((seg_end_minus_start.x * seg_start_local.x) + (seg_end_minus_start.y * seg_start_local.y));
|
||||
const float c = sq(seg_start_local.x) + sq(seg_start_local.y) - sq(radius);
|
||||
const float delta = sq(b) - (4.0f * a * c);
|
||||
|
||||
// check for invalid data
|
||||
if (fabsf(a) < FLT_EPSILON) {
|
||||
return false;
|
||||
}
|
||||
if (isnan(a) || isnan(b) || isnan(c) || isnan(delta)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// check for invalid delta (i.e. discriminant)
|
||||
if (delta < 0.0f) {
|
||||
return false;
|
||||
}
|
||||
|
||||
const float delta_sqrt = safe_sqrt(delta);
|
||||
const float t1 = (-b + delta_sqrt) / (2.0f * a);
|
||||
const float t2 = (-b - delta_sqrt) / (2.0f * a);
|
||||
|
||||
// Three hit cases:
|
||||
// -o-> --|--> | | --|->
|
||||
// Impale(t1 hit,t2 hit), Poke(t1 hit,t2>1), ExitWound(t1<0, t2 hit),
|
||||
|
||||
// Three miss cases:
|
||||
// -> o o -> | -> |
|
||||
// FallShort (t1>1,t2>1), Past (t1<0,t2<0), CompletelyInside(t1<0, t2>1)
|
||||
|
||||
// intersection = new Vector3(E.x + t1 * d.x, secondPoint.y, E.y + t1 * d.y);
|
||||
// intersection.x = seg_start.x + t1 * seg_end_minus_start.x;
|
||||
// intersection.y = seg_start.y + t1 * seg_end_minus_start.y;
|
||||
|
||||
if ((t1 >= 0.0f) && (t1 <= 1.0f)) {
|
||||
// t1 is the intersection, and it is closer than t2 (since t1 uses -b - discriminant)
|
||||
// Impale, Poke
|
||||
intersection = seg_start + (seg_end_minus_start * t1);
|
||||
return true;
|
||||
}
|
||||
|
||||
// here t1 did not intersect so we are either started inside the sphere or completely past it
|
||||
if ((t2 >= 0.0f) && (t2 <= 1.0f)) {
|
||||
// ExitWound
|
||||
intersection = seg_start + (seg_end_minus_start * t2);
|
||||
return true;
|
||||
}
|
||||
|
||||
// no intersection: FallShort, Past or CompletelyInside
|
||||
return false;
|
||||
}
|
||||
|
||||
// only define for float
|
||||
template float Vector2<float>::length(void) const;
|
||||
template float Vector2<float>::operator *(const Vector2<float> &v) const;
|
||||
@ -192,6 +256,7 @@ template bool Vector2<float>::is_nan(void) const;
|
||||
template bool Vector2<float>::is_inf(void) const;
|
||||
template float Vector2<float>::angle(const Vector2<float> &v) const;
|
||||
template bool Vector2<float>::segment_intersection(const Vector2<float>& seg1_start, const Vector2<float>& seg1_end, const Vector2<float>& seg2_start, const Vector2<float>& seg2_end, Vector2<float>& intersection);
|
||||
template bool Vector2<float>::circle_segment_intersection(const Vector2<float>& seg_start, const Vector2<float>& seg_end, const Vector2<float>& circle_center, float radius, Vector2<float>& intersection);
|
||||
|
||||
template bool Vector2<long>::operator ==(const Vector2<long> &v) const;
|
||||
|
||||
|
@ -226,6 +226,10 @@ struct Vector2
|
||||
// the point of intersection is returned in the intersection argument
|
||||
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);
|
||||
|
||||
// find the intersection between a line segment and a circle
|
||||
// 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);
|
||||
|
||||
};
|
||||
|
||||
typedef Vector2<int16_t> Vector2i;
|
||||
|
Loading…
Reference in New Issue
Block a user