mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Math: create and use INTERNAL_ERROR macro so we get line numbers
This commit is contained in:
parent
7befe84f0c
commit
58a8e54d83
@ -266,7 +266,7 @@ T constrain_value(const T amt, const T low, const T high)
|
|||||||
// errors through any function that uses constrain_value(). The normal
|
// errors through any function that uses constrain_value(). The normal
|
||||||
// float semantics already handle -Inf and +Inf
|
// float semantics already handle -Inf and +Inf
|
||||||
if (isnan(amt)) {
|
if (isnan(amt)) {
|
||||||
AP::internalerror().error(AP_InternalError::error_t::constraining_nan);
|
INTERNAL_ERROR(AP_InternalError::error_t::constraining_nan);
|
||||||
return (low + high) / 2;
|
return (low + high) / 2;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -368,14 +368,14 @@ void Quaternion::from_rotation(enum Rotation rotation)
|
|||||||
|
|
||||||
case ROTATION_CUSTOM:
|
case ROTATION_CUSTOM:
|
||||||
// Error; custom rotations not supported
|
// Error; custom rotations not supported
|
||||||
AP::internalerror().error(AP_InternalError::error_t::flow_of_control);
|
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
|
||||||
return;
|
return;
|
||||||
|
|
||||||
case ROTATION_MAX:
|
case ROTATION_MAX:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
// rotation invalid
|
// rotation invalid
|
||||||
AP::internalerror().error(AP_InternalError::error_t::bad_rotation);
|
INTERNAL_ERROR(AP_InternalError::error_t::bad_rotation);
|
||||||
}
|
}
|
||||||
|
|
||||||
// rotate this quaternion by the given rotation
|
// rotate this quaternion by the given rotation
|
||||||
|
@ -253,13 +253,13 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
}
|
}
|
||||||
case ROTATION_CUSTOM:
|
case ROTATION_CUSTOM:
|
||||||
// Error: caller must perform custom rotations via matrix multiplication
|
// Error: caller must perform custom rotations via matrix multiplication
|
||||||
AP::internalerror().error(AP_InternalError::error_t::flow_of_control);
|
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
|
||||||
return;
|
return;
|
||||||
case ROTATION_MAX:
|
case ROTATION_MAX:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
// rotation invalid
|
// rotation invalid
|
||||||
AP::internalerror().error(AP_InternalError::error_t::bad_rotation);
|
INTERNAL_ERROR(AP_InternalError::error_t::bad_rotation);
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
|
Loading…
Reference in New Issue
Block a user