mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Math: consolidate error checking
This commit is contained in:
parent
4ffc559ccc
commit
f534963413
@ -200,7 +200,8 @@ bool Vector2<T>::circle_segment_intersection(const Vector2<T>& seg_start, const
|
||||
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);
|
||||
|
||||
if (isnan(a) || isnan(b) || isnan(c)) {
|
||||
// check for invalid data
|
||||
if (::is_zero(a) || isnan(a) || isnan(b) || isnan(c)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -210,11 +211,6 @@ bool Vector2<T>::circle_segment_intersection(const Vector2<T>& seg_start, const
|
||||
return false;
|
||||
}
|
||||
|
||||
// check for invalid data
|
||||
if (::is_zero(a)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// check for invalid delta (i.e. discriminant)
|
||||
if (delta < 0.0f) {
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user